1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-02-20 10:54:14 +01:00

LP-512 Addressed remainging PR comments.

This commit is contained in:
Vladimir Zidar 2017-05-30 16:31:39 +02:00
parent fb696dc893
commit 4eeb983f2d
70 changed files with 114 additions and 3649 deletions

View File

@ -7,7 +7,7 @@
#include <stdint.h>
#include "inc/dcc_stdio.h"
#ifdef STM32F4XX
#ifdef STM32F4
# include <stm32f4xx.h>
#endif
#ifdef STM32F3
@ -16,6 +16,9 @@
#ifdef STM32F2XX
# include <stm32f2xx.h>
#endif
#ifdef STM32F1
# include <stm32f10x.h>
#endif
#define FAULT_TRAMPOLINE(_vec) \
__attribute__((naked, no_instrument_function)) \

View File

@ -153,6 +153,11 @@ ifeq ($(USE_CXX),YES)
CPPSRC += $(FLIGHTLIB)/mini_cpp.cpp
endif
ifeq ($(DEBUG), YES)
SRC += $(FLIGHTLIB)/dcc_stdio.c
SRC += $(FLIGHTLIB)/cm3_fault_handlers.c
endif
## Modules
SRC += $(foreach mod, $(MODULES), $(sort $(wildcard $(OPMODULEDIR)/$(mod)/*.c)))
CPPSRC += $(foreach mod, $(MODULES), $(sort $(wildcard $(OPMODULEDIR)/$(mod)/*.cpp)))

View File

@ -221,15 +221,9 @@ void PIOS_BOARD_Sensors_Configure()
}
#endif /* PIOS_INCLUDE_ADC */
// internal bmp280 baro
// internal MPU6000 imu (i2c)
// external ETASV3 Eagletree Airspeed v3
// external MS4525D PixHawk Airpeed based on MS4525DO
// BMA180 accelerometer?
// bmp085/bmp180 baro
// hmc5843 mag
// i2c esc (?)
// UBX DCC

View File

@ -1,8 +1,9 @@
/**
******************************************************************************
*
* @file pios_servp_config.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2013.
* @file pios_servo_config.h
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2017
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2013.
* @brief Architecture specific macros and definitions
* --
* @see The GNU Public License (GPL) Version 3
@ -28,7 +29,7 @@
/**
* Generic servo pin configuration structure for an STM32F4xx
* Generic servo pin configuration structure for an STM32F30X
*/
#define TIM_SERVO_CHANNEL_CONFIG(_timer, _channel, _gpio, _pin) \
{ \

View File

@ -1,5 +1,27 @@
/**
******************************************************************************
*
* @file pios_usart_config.h
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2017
* @brief Architecture specific macros and definitions
* --
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* pios_usart_config.h
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PIOS_USART_CONFIG_H_

View File

@ -8,7 +8,7 @@
*
* @file pios_adc.c
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2017.
* @brief Analog to Digital converstion routines
* @brief Analog to Digital conversion routines
* @see The GNU Public License (GPL) Version 3
*****************************************************************************/
/*

View File

@ -3,12 +3,12 @@
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_BOOTLOADER Functions
* @brief HAL code to interface to the OpenPilot AHRS module
* @{
* @brief Bootloader Helper Functions
*
*
* @file pios_bl_helper.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Bootloader Helper Functions
* @author The LibrePilot Project, http://www.librepilot.org Copyright(C) 2017.
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/

View File

@ -1,429 +0,0 @@
/**
******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_CAN PiOS CAN interface layer
* @brief CAN interface for PiOS
* @{
*
* @file pios_can.c
* @author Tau Labs, http://taulabs.org, Copyright (C) 2013-2014
* @author dRonin, http://dronin.org, Copyright (C) 2016
* @brief PiOS CAN interface header
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "pios.h"
#if defined(PIOS_INCLUDE_CAN)
#include "pios_can_priv.h"
/* Provide a COM driver */
static void PIOS_CAN_RegisterRxCallback(uintptr_t can_id, pios_com_callback rx_in_cb, uintptr_t context);
static void PIOS_CAN_RegisterTxCallback(uintptr_t can_id, pios_com_callback tx_out_cb, uintptr_t context);
static void PIOS_CAN_TxStart(uintptr_t can_id, uint16_t tx_bytes_avail);
static void PIOS_CAN_RxStart(uintptr_t can_id, uint16_t rx_bytes_avail);
const struct pios_com_driver pios_can_com_driver = {
.tx_start = PIOS_CAN_TxStart,
.rx_start = PIOS_CAN_RxStart,
.bind_tx_cb = PIOS_CAN_RegisterTxCallback,
.bind_rx_cb = PIOS_CAN_RegisterRxCallback,
};
enum pios_can_dev_magic {
PIOS_CAN_DEV_MAGIC = 0x41fa834A,
};
// ! Structure for an initialized CAN handle
struct pios_can_dev {
enum pios_can_dev_magic magic;
const struct pios_can_cfg *cfg;
pios_com_callback rx_in_cb;
uintptr_t rx_in_context;
pios_com_callback tx_out_cb;
uintptr_t tx_out_context;
};
// Local constants
#define CAN_COM_ID 0x11
#define MAX_SEND_LEN 8
void USB_HP_CAN1_TX_IRQHandler(void);
static bool PIOS_CAN_validate(struct pios_can_dev *can_dev)
{
return can_dev->magic == PIOS_CAN_DEV_MAGIC;
}
static struct pios_can_dev *PIOS_CAN_alloc(void)
{
struct pios_can_dev *can_dev;
can_dev = (struct pios_can_dev *)PIOS_malloc(sizeof(*can_dev));
if (!can_dev) {
return NULL;
}
memset(can_dev, 0, sizeof(*can_dev));
can_dev->magic = PIOS_CAN_DEV_MAGIC;
return can_dev;
}
// ! The local handle for the CAN device
static struct pios_can_dev *can_dev;
/**
* Initialize the CAN driver and return an opaque id
* @param[out] id the CAN interface handle
* @param[in] cfg the configuration structure
* @return 0 if successful, negative otherwise
*/
int32_t PIOS_CAN_Init(uintptr_t *can_id, const struct pios_can_cfg *cfg)
{
PIOS_DEBUG_Assert(can_id);
PIOS_DEBUG_Assert(cfg);
can_dev = (struct pios_can_dev *)PIOS_CAN_alloc();
if (!can_dev) {
goto out_fail;
}
/* Bind the configuration to the device instance */
can_dev->cfg = cfg;
/* Configure the CAN device */
RCC_APB1PeriphClockCmd(RCC_APB1Periph_CAN1, ENABLE);
/* Map pins to CAN function */
if (can_dev->cfg->remap) {
if (can_dev->cfg->rx.gpio != 0) {
GPIO_PinAFConfig(can_dev->cfg->rx.gpio,
can_dev->cfg->rx.pin_source,
can_dev->cfg->remap);
}
if (can_dev->cfg->tx.gpio != 0) {
GPIO_PinAFConfig(can_dev->cfg->tx.gpio,
can_dev->cfg->tx.pin_source,
can_dev->cfg->remap);
}
}
/* Initialize the CAN Rx and Tx pins */
if (can_dev->cfg->rx.gpio != 0) {
GPIO_Init(can_dev->cfg->rx.gpio, (GPIO_InitTypeDef *)&can_dev->cfg->rx.init);
}
if (can_dev->cfg->tx.gpio != 0) {
GPIO_Init(can_dev->cfg->tx.gpio, (GPIO_InitTypeDef *)&can_dev->cfg->tx.init);
}
*can_id = (uintptr_t)can_dev;
CAN_DeInit(can_dev->cfg->regs);
CAN_Init(can_dev->cfg->regs, (CAN_InitTypeDef *)&can_dev->cfg->init);
/* CAN filter init */
CAN_FilterInitTypeDef CAN_FilterInitStructure;
CAN_FilterInitStructure.CAN_FilterNumber = 0;
CAN_FilterInitStructure.CAN_FilterMode = CAN_FilterMode_IdMask;
CAN_FilterInitStructure.CAN_FilterScale = CAN_FilterScale_32bit;
CAN_FilterInitStructure.CAN_FilterIdHigh = 0x0000;
CAN_FilterInitStructure.CAN_FilterIdLow = 0x0000;
CAN_FilterInitStructure.CAN_FilterMaskIdHigh = 0x0000;
CAN_FilterInitStructure.CAN_FilterMaskIdLow = 0x0000;
CAN_FilterInitStructure.CAN_FilterFIFOAssignment = 1;
CAN_FilterInitStructure.CAN_FilterActivation = ENABLE;
CAN_FilterInit(&CAN_FilterInitStructure);
// Enable the receiver IRQ
NVIC_Init((NVIC_InitTypeDef *)&can_dev->cfg->rx_irq.init);
NVIC_Init((NVIC_InitTypeDef *)&can_dev->cfg->tx_irq.init);
return 0;
out_fail:
return -1;
}
static void PIOS_CAN_RxStart(uintptr_t can_id, uint16_t rx_bytes_avail)
{
struct pios_can_dev *can_dev = (struct pios_can_dev *)can_id;
bool valid = PIOS_CAN_validate(can_dev);
PIOS_Assert(valid);
CAN_ITConfig(can_dev->cfg->regs, CAN_IT_FMP1, ENABLE);
}
static void PIOS_CAN_TxStart(uintptr_t can_id, uint16_t tx_bytes_avail)
{
struct pios_can_dev *can_dev = (struct pios_can_dev *)can_id;
bool valid = PIOS_CAN_validate(can_dev);
PIOS_Assert(valid);
CAN_ITConfig(can_dev->cfg->regs, CAN_IT_TME, ENABLE);
USB_HP_CAN1_TX_IRQHandler();
}
static void PIOS_CAN_RegisterRxCallback(uintptr_t can_id, pios_com_callback rx_in_cb, uintptr_t context)
{
struct pios_can_dev *can_dev = (struct pios_can_dev *)can_id;
bool valid = PIOS_CAN_validate(can_dev);
PIOS_Assert(valid);
/*
* Order is important in these assignments since ISR uses _cb
* field to determine if it's ok to dereference _cb and _context
*/
can_dev->rx_in_context = context;
can_dev->rx_in_cb = rx_in_cb;
}
static void PIOS_CAN_RegisterTxCallback(uintptr_t can_id, pios_com_callback tx_out_cb, uintptr_t context)
{
struct pios_can_dev *can_dev = (struct pios_can_dev *)can_id;
bool valid = PIOS_CAN_validate(can_dev);
PIOS_Assert(valid);
/*
* Order is important in these assignments since ISR uses _cb
* field to determine if it's ok to dereference _cb and _context
*/
can_dev->tx_out_context = context;
can_dev->tx_out_cb = tx_out_cb;
}
// ! The mapping of message types to CAN BUS StdID
static uint32_t pios_can_message_stdid[PIOS_CAN_LAST] = {
[PIOS_CAN_GIMBAL] = 0x130,
};
// ! The mapping of message types to CAN BUS StdID
static struct pios_queue *pios_can_queues[PIOS_CAN_LAST];
/**
* Process received CAN messages and push them out any corresponding
* queues. Called from ISR.
*/
static bool process_received_message(CanRxMsg message)
{
// Look for a known message that matches this CAN StdId
uint32_t msg_id;
for (msg_id = 0; msg_id < PIOS_CAN_LAST && pios_can_message_stdid[msg_id] != message.StdId; msg_id++) {
;
}
// If StdId is not one of the known messages, bail out
if (msg_id == PIOS_CAN_LAST) {
return false;
}
// Get the queue for this message and send the data
struct pios_queue *queue = pios_can_queues[msg_id];
if (queue == NULL) {
return false;
}
bool woken = false;
PIOS_Queue_Send_FromISR(queue, message.Data, &woken);
return woken;
}
/**
* Create a queue to receive messages for a particular message
* and return it
* @param[in] id the CAN device ID
* @param[in] msg_id The message ID (std ID < 0x7FF)
*/
struct pios_queue *PIOS_CAN_RegisterMessageQueue(uintptr_t id, enum pios_can_messages msg_id)
{
// Fetch the size of this message type or error if unknown
uint32_t bytes;
switch (msg_id) {
case PIOS_CAN_GIMBAL:
bytes = sizeof(struct pios_can_gimbal_message);
break;
default:
return NULL;
}
// Return existing queue if created
if (pios_can_queues[msg_id] != NULL) {
return pios_can_queues[msg_id];
}
// Create a queue that can manage the data message size
struct pios_queue *queue;
queue = PIOS_Queue_Create(2, bytes);
if (queue == NULL) {
return NULL;
}
// Store the queue handle for the driver
pios_can_queues[msg_id] = queue;
return queue;
}
// Map the specific IRQ handlers to the device handle
static void PIOS_CAN_RxGeneric(void);
static void PIOS_CAN_TxGeneric(void);
void CAN1_RX1_IRQHandler(void)
{
#if defined(PIOS_INCLUDE_CHIBIOS)
CH_IRQ_PROLOGUE();
#endif /* defined(PIOS_INCLUDE_CHIBIOS) */
PIOS_CAN_RxGeneric();
#if defined(PIOS_INCLUDE_CHIBIOS)
CH_IRQ_EPILOGUE();
#endif /* defined(PIOS_INCLUDE_CHIBIOS) */
}
void USB_HP_CAN1_TX_IRQHandler(void)
{
#if defined(PIOS_INCLUDE_CHIBIOS)
CH_IRQ_PROLOGUE();
#endif /* defined(PIOS_INCLUDE_CHIBIOS) */
PIOS_CAN_TxGeneric();
#if defined(PIOS_INCLUDE_CHIBIOS)
CH_IRQ_EPILOGUE();
#endif /* defined(PIOS_INCLUDE_CHIBIOS) */
}
/**
* @brief This function handles CAN1 RX1 request.
* @note We are using RX1 instead of RX0 to avoid conflicts with the
* USB IRQ handler.
*/
static void PIOS_CAN_RxGeneric(void)
{
CAN_ClearITPendingBit(can_dev->cfg->regs, CAN_IT_FMP1);
bool valid = PIOS_CAN_validate(can_dev);
PIOS_Assert(valid);
CanRxMsg RxMessage;
CAN_Receive(CAN1, CAN_FIFO1, &RxMessage);
bool rx_need_yield = false;
if (RxMessage.StdId == CAN_COM_ID) {
if (can_dev->rx_in_cb) {
(void)(can_dev->rx_in_cb)(can_dev->rx_in_context, RxMessage.Data, RxMessage.DLC, NULL, &rx_need_yield);
}
} else {
rx_need_yield = process_received_message(RxMessage);
}
}
/**
* @brief This function handles CAN1 TX irq and sends more data if available
*/
static void PIOS_CAN_TxGeneric(void)
{
CAN_ClearITPendingBit(can_dev->cfg->regs, CAN_IT_TME);
bool valid = PIOS_CAN_validate(can_dev);
PIOS_Assert(valid);
bool tx_need_yield = false;
if (can_dev->tx_out_cb) {
// Prepare CAN message structure
CanTxMsg msg;
msg.StdId = CAN_COM_ID;
msg.ExtId = 0;
msg.IDE = CAN_ID_STD;
msg.RTR = CAN_RTR_DATA;
msg.DLC = (can_dev->tx_out_cb)(can_dev->tx_out_context, msg.Data, MAX_SEND_LEN, NULL, &tx_need_yield);
// Send message and get mailbox number
if (msg.DLC > 0) {
CAN_Transmit(can_dev->cfg->regs, &msg);
} else {
CAN_ITConfig(can_dev->cfg->regs, CAN_IT_TME, DISABLE);
}
// TODO: deal with failure to send and keep the message to retransmit
}
}
/**
* PIOS_CAN_TxData transmits a data message with a specified ID
* @param[in] id the CAN device ID
* @param[in] msg_id The message ID (std ID < 0x7FF)
* @param[in] data Pointer to data message
* @returns number of bytes sent if successful, -1 if not
*/
int32_t PIOS_CAN_TxData(uintptr_t id, enum pios_can_messages msg_id, uint8_t *data)
{
// Fetch the size of this message type or error if unknown
uint32_t bytes;
switch (msg_id) {
case PIOS_CAN_GIMBAL:
bytes = sizeof(struct pios_can_gimbal_message);
break;
default:
return -1;
}
// Look up the CAN BUS Standard ID for this message type
uint32_t std_id = pios_can_message_stdid[msg_id];
// Format and send the message
CanTxMsg msg;
msg.StdId = std_id & 0x7FF;
msg.ExtId = 0;
msg.IDE = CAN_ID_STD;
msg.RTR = CAN_RTR_DATA;
msg.DLC = (bytes > 8) ? 8 : bytes;
memcpy(msg.Data, data, msg.DLC);
CAN_Transmit(can_dev->cfg->regs, &msg);
return msg.DLC;
}
#endif /* PIOS_INCLUDE_CAN */
/**
* @}
* @}
*/

View File

@ -36,10 +36,6 @@
#if defined(PIOS_INCLUDE_I2C)
#if defined(PIOS_INCLUDE_FREERTOS)
#define USE_FREERTOS
#endif
#include <pios_i2c_priv.h>
enum i2c_adapter_state {
@ -241,7 +237,7 @@ static void go_stopped(struct pios_i2c_adapter *i2c_adapter, bool *woken)
if (i2c_adapter->callback) {
i2c_adapter_callback_handler(i2c_adapter, woken);
} else {
#ifdef USE_FREERTOS
#ifdef PIOS_INCLUDE_FREERTOS
signed portBASE_TYPE pxHigherPriorityTaskWoken = pdFALSE;
if (xSemaphoreGiveFromISR(i2c_adapter->sem_ready, &pxHigherPriorityTaskWoken) != pdTRUE) {
#if defined(I2C_HALT_ON_ERRORS)
@ -251,7 +247,7 @@ static void go_stopped(struct pios_i2c_adapter *i2c_adapter, bool *woken)
if (pxHigherPriorityTaskWoken == pdTRUE) {
*woken = true;
}
#endif /* USE_FREERTOS */
#endif /* PIOS_INCLUDE_FREERTOS */
}
}
@ -536,12 +532,12 @@ static bool PIOS_I2C_validate(struct pios_i2c_adapter *i2c_adapter)
return i2c_adapter->magic == PIOS_I2C_DEV_MAGIC;
}
#if defined(PIOS_INCLUDE_CHIBIOS) && 0
static struct pios_i2c_dev *PIOS_I2C_alloc(void)
#if defined(PIOS_INCLUDE_FREERTOS)
static struct pios_i2c_adapter *PIOS_I2C_alloc(void)
{
struct pios_i2c_dev *i2c_adapter;
struct pios_i2c_adapter *i2c_adapter;
i2c_adapter = (struct pios_i2c_adapter *)PIOS_malloc(sizeof(*i2c_adapter));
i2c_adapter = (struct pios_i2c_adapter *)pios_malloc(sizeof(*i2c_adapter));
if (!i2c_adapter) {
return NULL;
}
@ -621,7 +617,7 @@ int32_t PIOS_I2C_Transfer(uint32_t i2c_id, const struct pios_i2c_txn txn_list[],
bool semaphore_success = true;
#ifdef USE_FREERTOS
#ifdef PIOS_INCLUDE_FREERTOS
/* Lock the bus */
portTickType timeout;
timeout = i2c_adapter->cfg->transfer_timeout_ms / portTICK_RATE_MS;
@ -636,7 +632,7 @@ int32_t PIOS_I2C_Transfer(uint32_t i2c_id, const struct pios_i2c_txn txn_list[],
}
i2c_adapter->busy = 1;
PIOS_IRQ_Enable();
#endif /* USE_FREERTOS */
#endif /* PIOS_INCLUDE_FREERTOS */
PIOS_DEBUG_Assert(i2c_adapter->curr_state == I2C_STATE_STOPPED);
@ -645,7 +641,7 @@ int32_t PIOS_I2C_Transfer(uint32_t i2c_id, const struct pios_i2c_txn txn_list[],
i2c_adapter->bus_error = false;
i2c_adapter->nack = false;
#ifdef USE_FREERTOS
#ifdef PIOS_INCLUDE_FREERTOS
/* Make sure the done/ready semaphore is consumed before we start */
semaphore_success &= (xSemaphoreTake(i2c_adapter->sem_ready, timeout) == pdTRUE);
#endif
@ -656,12 +652,12 @@ int32_t PIOS_I2C_Transfer(uint32_t i2c_id, const struct pios_i2c_txn txn_list[],
i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_START, &dummy);
/* Wait for the transfer to complete */
#ifdef USE_FREERTOS
#ifdef PIOS_INCLUDE_FREERTOS
semaphore_success &= (xSemaphoreTake(i2c_adapter->sem_ready, timeout) == pdTRUE);
xSemaphoreGive(i2c_adapter->sem_ready);
#endif /* USE_FREERTOS */
#endif /* PIOS_INCLUDE_FREERTOS */
#ifdef USE_FREERTOS
#ifdef PIOS_INCLUDE_FREERTOS
/* Unlock the bus */
xSemaphoreGive(i2c_adapter->sem_busy);
#if defined(PIOS_I2C_DIAGNOSTICS)
@ -673,7 +669,7 @@ int32_t PIOS_I2C_Transfer(uint32_t i2c_id, const struct pios_i2c_txn txn_list[],
PIOS_IRQ_Disable();
i2c_adapter->busy = 0;
PIOS_IRQ_Enable();
#endif /* USE_FREERTOS */
#endif /* PIOS_INCLUDE_FREERTOS */
return !semaphore_success ? -2 :
i2c_adapter->bus_error ? -1 :
@ -717,7 +713,7 @@ int32_t PIOS_I2C_Transfer_Callback(uint32_t i2c_id, const struct pios_i2c_txn tx
PIOS_DEBUG_Assert(txn_list);
PIOS_DEBUG_Assert(num_txns);
#ifdef USE_FREERTOS
#ifdef PIOS_INCLUDE_FREERTOS
/* Lock the bus */
portTickType timeout;
timeout = i2c_adapter->cfg->transfer_timeout_ms / portTICK_RATE_MS;
@ -732,7 +728,7 @@ int32_t PIOS_I2C_Transfer_Callback(uint32_t i2c_id, const struct pios_i2c_txn tx
}
i2c_adapter->busy = 1;
PIOS_IRQ_Enable();
#endif /* USE_FREERTOS */
#endif /* PIOS_INCLUDE_FREERTOS */
return PIOS_I2C_Transfer_Callback_Internal(i2c_adapter, txn_list, num_txns, callback);
}
@ -749,7 +745,7 @@ int32_t PIOS_I2C_Transfer_CallbackFromISR(uint32_t i2c_id, const struct pios_i2c
PIOS_DEBUG_Assert(txn_list);
PIOS_DEBUG_Assert(num_txns);
#ifdef USE_FREERTOS
#ifdef PIOS_INCLUDE_FREERTOS
signed portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
/* Lock the bus */
@ -770,7 +766,7 @@ int32_t PIOS_I2C_Transfer_CallbackFromISR(uint32_t i2c_id, const struct pios_i2c
}
i2c_adapter->busy = 1;
PIOS_IRQ_Enable();
#endif /* USE_FREERTOS */
#endif /* PIOS_INCLUDE_FREERTOS */
return PIOS_I2C_Transfer_Callback_Internal(i2c_adapter, txn_list, num_txns, callback);
}
@ -778,7 +774,7 @@ int32_t PIOS_I2C_Transfer_CallbackFromISR(uint32_t i2c_id, const struct pios_i2c
static bool i2c_adapter_callback_handler(struct pios_i2c_adapter *i2c_adapter, bool *woken)
{
#ifdef USE_FREERTOS
#ifdef PIOS_INCLUDE_FREERTOS
/* Unlock the bus */
signed portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
xSemaphoreGiveFromISR(i2c_adapter->sem_busy, &xHigherPriorityTaskWoken);
@ -789,7 +785,7 @@ static bool i2c_adapter_callback_handler(struct pios_i2c_adapter *i2c_adapter, b
PIOS_IRQ_Disable();
i2c_adapter->busy = 0;
PIOS_IRQ_Enable();
#endif /* USE_FREERTOS */
#endif /* PIOS_INCLUDE_FREERTOS */
// Execute user supplied function

View File

@ -1,3 +1,33 @@
/**
******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_TIM Timer Functions
* @brief PIOS Timer control code
* @{
*
* @file pios_tim.c
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2017.
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
* @brief Sets up timers and ways to register callbacks on them
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "pios.h"
#ifdef PIOS_INCLUDE_TIM

View File

@ -6,7 +6,7 @@
* @brief PIOS Comamnds to initialize and clear watchdog timer
* @{
*
* @file pios_spi.c
* @file pios_wdg.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
* Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org)
* @brief Hardware Abstraction Layer for SPI ports of STM32

View File

@ -3,15 +3,10 @@ BOARD_REVISION := 0x03
BOOTLOADER_VERSION := 0x04
HW_TYPE := 0x01
MCU := cortex-m4
PIOS_DEVLIB := $(PIOS)/stm32f30x
CHIP := STM32F303xC
BOARD := STM32F303CCT_CC_Rev1
MODEL := HD
MODEL_SUFFIX := _CC
OPENOCD_JTAG_CONFIG := foss-jtag.revb.cfg
OPENOCD_CONFIG := stm32f1x.cfg
OPENOCD_CONFIG := stm32f3x.cfg
# Note: These must match the values in link_$(BOARD)_memory.ld
BL_BANK_BASE := 0x08000000 # Start of bootloader flash

View File

@ -58,6 +58,7 @@ OPTMODULES += Battery
OPTMODULES += ComUsbBridge
OPTMODULES += UAVOMSPBridge
OPTMODULES += UAVOMavlinkBridge
OPTMODULES += UAVOFrSKYSensorHubBridge
SRC += $(FLIGHTLIB)/notification.c
@ -86,11 +87,6 @@ ifndef TESTAPP
SRC += $(PIOSCOMMON)/pios_flashfs_logfs.c
SRC += $(PIOSCOMMON)/pios_flash_jedec.c
#ifeq ($(DEBUG), YES)
SRC += $(OPSYSTEM)/dcc_stdio.c
SRC += $(OPSYSTEM)/cm3_fault_handlers.c
#endif
## Misc library functions
SRC += $(FLIGHTLIB)/instrumentation.c
SRC += $(FLIGHTLIB)/paths.c

View File

@ -1,93 +0,0 @@
/*
* cm3_fault_handlers.c
*
* Created on: Apr 24, 2011
* Author: msmith
*/
#include <stdint.h>
#include "inc/dcc_stdio.h"
#ifdef STM32F4XX
# include <stm32f4xx.h>
#endif
#ifdef STM32F3
# include <stm32f30x.h>
#endif
#ifdef STM32F2XX
# include <stm32f2xx.h>
#endif
#define FAULT_TRAMPOLINE(_vec) \
__attribute__((naked, no_instrument_function)) \
void \
_vec##_Handler(void) \
{ \
__asm(".syntax unified\n" \
"MOVS R0, #4 \n" \
"MOV R1, LR \n" \
"TST R0, R1 \n" \
"BEQ 1f \n" \
"MRS R0, PSP \n" \
"B " #_vec "_Handler2 \n" \
"1: \n" \
"MRS R0, MSP \n" \
"B " #_vec "_Handler2 \n" \
".syntax divided\n"); \
} \
struct hack
struct cm3_frame {
uint32_t r0;
uint32_t r1;
uint32_t r2;
uint32_t r3;
uint32_t r12;
uint32_t lr;
uint32_t pc;
uint32_t psr;
};
FAULT_TRAMPOLINE(HardFault);
FAULT_TRAMPOLINE(BusFault);
FAULT_TRAMPOLINE(UsageFault);
/* this is a hackaround to avoid an issue where dereferencing SCB seems to result in bad codegen and a link error */
#define SCB_REG(_reg) (*(uint32_t *)&(SCB->_reg))
void HardFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nHARD FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(HFSR));
dbg_write_char('\n');
for (;;) {
;
}
}
void BusFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nBUS FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(CFSR));
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(BFAR));
dbg_write_char('\n');
for (;;) {
;
}
}
void UsageFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nUSAGE FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(CFSR));
dbg_write_char('\n');
for (;;) {
;
}
}

View File

@ -33,22 +33,14 @@
#include <pios_usbhook.h> /* PIOS_USBHOOK_* */
#include <pios_usb_util.h> /* PIOS_USB_UTIL_AsciiToUtf8 */
static const uint8_t usb_product_id[28] = {
static const uint8_t usb_product_id[12] = {
sizeof(usb_product_id),
USB_DESC_TYPE_STRING,
'C', 0,
'o', 0,
'p', 0,
't', 0,
'e', 0,
'r', 0,
'C', 0,
'o', 0,
'n', 0,
't', 0,
'r', 0,
'o', 0,
'l', 0,
'F', 0,
'3', 0,
'D', 0,
};
static uint8_t usb_serial_number[2 + PIOS_SYS_SERIAL_NUM_ASCII_LEN * 2 + (sizeof(PIOS_USB_BOARD_SN_SUFFIX) - 1) * 2] = {

View File

@ -25,7 +25,7 @@ endif
include ../board-info.mk
include $(FLIGHT_ROOT_DIR)/make/firmware-defs.mk
# REVO C++ support
# REVO C++ support
USE_CXX = YES
# ARM DSP library
@ -88,11 +88,6 @@ ifndef TESTAPP
SRC += $(PIOSCOMMON)/pios_flashfs_logfs.c
SRC += $(PIOSCOMMON)/pios_flash_jedec.c
#ifeq ($(DEBUG), YES)
SRC += $(OPSYSTEM)/dcc_stdio.c
SRC += $(OPSYSTEM)/cm3_fault_handlers.c
#endif
## Misc library functions
SRC += $(FLIGHTLIB)/instrumentation.c
SRC += $(FLIGHTLIB)/paths.c

View File

@ -1,90 +0,0 @@
/*
* cm3_fault_handlers.c
*
* Created on: Apr 24, 2011
* Author: msmith
*/
#include <stdint.h>
#include "inc/dcc_stdio.h"
#ifdef STM32F4XX
# include <stm32f4xx.h>
#endif
#ifdef STM32F2XX
# include <stm32f2xx.h>
#endif
#define FAULT_TRAMPOLINE(_vec) \
__attribute__((naked, no_instrument_function)) \
void \
_vec##_Handler(void) \
{ \
__asm(".syntax unified\n" \
"MOVS R0, #4 \n" \
"MOV R1, LR \n" \
"TST R0, R1 \n" \
"BEQ 1f \n" \
"MRS R0, PSP \n" \
"B " #_vec "_Handler2 \n" \
"1: \n" \
"MRS R0, MSP \n" \
"B " #_vec "_Handler2 \n" \
".syntax divided\n"); \
} \
struct hack
struct cm3_frame {
uint32_t r0;
uint32_t r1;
uint32_t r2;
uint32_t r3;
uint32_t r12;
uint32_t lr;
uint32_t pc;
uint32_t psr;
};
FAULT_TRAMPOLINE(HardFault);
FAULT_TRAMPOLINE(BusFault);
FAULT_TRAMPOLINE(UsageFault);
/* this is a hackaround to avoid an issue where dereferencing SCB seems to result in bad codegen and a link error */
#define SCB_REG(_reg) (*(uint32_t *)&(SCB->_reg))
void HardFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nHARD FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(HFSR));
dbg_write_char('\n');
for (;;) {
;
}
}
void BusFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nBUS FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(CFSR));
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(BFAR));
dbg_write_char('\n');
for (;;) {
;
}
}
void UsageFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nUSAGE FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(CFSR));
dbg_write_char('\n');
for (;;) {
;
}
}

View File

@ -1,149 +0,0 @@
/***************************************************************************
* Copyright (C) 2008 by Dominic Rath *
* Dominic.Rath@gmx.de *
* Copyright (C) 2008 by Spencer Oliver *
* spen@spen-soft.co.uk *
* Copyright (C) 2008 by Frederik Kriewtz *
* frederik@kriewitz.eu *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License, or *
* (at your option) any later version. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#include "inc/dcc_stdio.h"
#define TARGET_REQ_TRACEMSG 0x00
#define TARGET_REQ_DEBUGMSG_ASCII 0x01
#define TARGET_REQ_DEBUGMSG_HEXMSG(size) (0x01 | ((size & 0xff) << 8))
#define TARGET_REQ_DEBUGCHAR 0x02
/* we use the cortex_m3 DCRDR reg to simulate a arm7_9 dcc channel
* DCRDR[7:0] is used by target for status
* DCRDR[15:8] is used by target for write buffer
* DCRDR[23:16] is used for by host for status
* DCRDR[31:24] is used for by host for write buffer */
#define NVIC_DBG_DATA_R (*((volatile unsigned short *)0xE000EDF8))
#define BUSY 1
void dbg_write(unsigned long dcc_data)
{
int len = 4;
while (len--) {
/* wait for data ready */
while (NVIC_DBG_DATA_R & BUSY) {
;
}
/* write our data and set write flag - tell host there is data*/
NVIC_DBG_DATA_R = (unsigned short)(((dcc_data & 0xff) << 8) | BUSY);
dcc_data >>= 8;
}
}
void dbg_trace_point(unsigned long number)
{
dbg_write(TARGET_REQ_TRACEMSG | (number << 8));
}
void dbg_write_u32(const unsigned long *val, long len)
{
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(4) | ((len & 0xffff) << 16));
while (len > 0) {
dbg_write(*val);
val++;
len--;
}
}
void dbg_write_u16(const unsigned short *val, long len)
{
unsigned long dcc_data;
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(2) | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = val[0]
| ((len > 1) ? val[1] << 16 : 0x0000);
dbg_write(dcc_data);
val += 2;
len -= 2;
}
}
void dbg_write_u8(const unsigned char *val, long len)
{
unsigned long dcc_data;
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(1) | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = val[0]
| ((len > 1) ? val[1] << 8 : 0x00)
| ((len > 2) ? val[2] << 16 : 0x00)
| ((len > 3) ? val[3] << 24 : 0x00);
dbg_write(dcc_data);
val += 4;
len -= 4;
}
}
void dbg_write_str(const char *msg)
{
long len;
unsigned long dcc_data;
for (len = 0; msg[len] && (len < 65536); len++) {
;
}
dbg_write(TARGET_REQ_DEBUGMSG_ASCII | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = msg[0]
| ((len > 1) ? msg[1] << 8 : 0x00)
| ((len > 2) ? msg[2] << 16 : 0x00)
| ((len > 3) ? msg[3] << 24 : 0x00);
dbg_write(dcc_data);
msg += 4;
len -= 4;
}
}
void dbg_write_char(char msg)
{
dbg_write(TARGET_REQ_DEBUGCHAR | ((msg & 0xff) << 16));
}
void dbg_write_hex32(const unsigned long val)
{
static const char hextab[] = {
'0', '1', '2', '3', '4', '5', '6', '7',
'8', '9', 'a', 'b', 'c', 'd', 'e', 'f'
};
for (int shift = 28; shift >= 0; shift -= 4) {
dbg_write_char(hextab[(val >> shift) & 0xf]);
}
}

View File

@ -1,36 +0,0 @@
/***************************************************************************
* Copyright (C) 2008 by Dominic Rath *
* Dominic.Rath@gmx.de *
* Copyright (C) 2008 by Spencer Oliver *
* spen@spen-soft.co.uk *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License, or *
* (at your option) any later version. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#ifndef DCC_STDIO_H
#define DCC_STDIO_H
void dbg_trace_point(unsigned long number);
void dbg_write_u32(const unsigned long *val, long len);
void dbg_write_u16(const unsigned short *val, long len);
void dbg_write_u8(const unsigned char *val, long len);
void dbg_write_str(const char *msg);
void dbg_write_char(char msg);
void dbg_write_hex32(const unsigned long val);
#endif /* DCC_STDIO_H */

View File

@ -3,13 +3,10 @@ BOARD_REVISION := 0x03
BOOTLOADER_VERSION := 0x04
HW_TYPE := 0x01
MCU := cortex-m4
PIOS_DEVLIB := $(PIOS)/stm32f30x
CHIP := STM32F303xE
OPENOCD_JTAG_CONFIG := foss-jtag.revb.cfg
OPENOCD_CONFIG := stm32f1x.cfg
OPENOCD_CONFIG := stm32f3x.cfg
BL_BANK_BASE := 0x08000000 # Start of bootloader flash
BL_BANK_SIZE := 0x00004000 # Should include BD_INFO region

View File

@ -58,6 +58,7 @@ OPTMODULES += Battery
OPTMODULES += ComUsbBridge
OPTMODULES += UAVOMSPBridge
OPTMODULES += UAVOMavlinkBridge
OPTMODULES += UAVOFrSKYSensorHubBridge
SRC += $(FLIGHTLIB)/notification.c
@ -86,11 +87,6 @@ ifndef TESTAPP
SRC += $(PIOSCOMMON)/pios_flashfs_logfs.c
SRC += $(PIOSCOMMON)/pios_flash_jedec.c
#ifeq ($(DEBUG), YES)
SRC += $(OPSYSTEM)/dcc_stdio.c
SRC += $(OPSYSTEM)/cm3_fault_handlers.c
#endif
## Misc library functions
SRC += $(FLIGHTLIB)/instrumentation.c
SRC += $(FLIGHTLIB)/paths.c

View File

@ -1,149 +0,0 @@
/***************************************************************************
* Copyright (C) 2008 by Dominic Rath *
* Dominic.Rath@gmx.de *
* Copyright (C) 2008 by Spencer Oliver *
* spen@spen-soft.co.uk *
* Copyright (C) 2008 by Frederik Kriewtz *
* frederik@kriewitz.eu *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License, or *
* (at your option) any later version. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#include "inc/dcc_stdio.h"
#define TARGET_REQ_TRACEMSG 0x00
#define TARGET_REQ_DEBUGMSG_ASCII 0x01
#define TARGET_REQ_DEBUGMSG_HEXMSG(size) (0x01 | ((size & 0xff) << 8))
#define TARGET_REQ_DEBUGCHAR 0x02
/* we use the cortex_m3 DCRDR reg to simulate a arm7_9 dcc channel
* DCRDR[7:0] is used by target for status
* DCRDR[15:8] is used by target for write buffer
* DCRDR[23:16] is used for by host for status
* DCRDR[31:24] is used for by host for write buffer */
#define NVIC_DBG_DATA_R (*((volatile unsigned short *)0xE000EDF8))
#define BUSY 1
void dbg_write(unsigned long dcc_data)
{
int len = 4;
while (len--) {
/* wait for data ready */
while (NVIC_DBG_DATA_R & BUSY) {
;
}
/* write our data and set write flag - tell host there is data*/
NVIC_DBG_DATA_R = (unsigned short)(((dcc_data & 0xff) << 8) | BUSY);
dcc_data >>= 8;
}
}
void dbg_trace_point(unsigned long number)
{
dbg_write(TARGET_REQ_TRACEMSG | (number << 8));
}
void dbg_write_u32(const unsigned long *val, long len)
{
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(4) | ((len & 0xffff) << 16));
while (len > 0) {
dbg_write(*val);
val++;
len--;
}
}
void dbg_write_u16(const unsigned short *val, long len)
{
unsigned long dcc_data;
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(2) | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = val[0]
| ((len > 1) ? val[1] << 16 : 0x0000);
dbg_write(dcc_data);
val += 2;
len -= 2;
}
}
void dbg_write_u8(const unsigned char *val, long len)
{
unsigned long dcc_data;
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(1) | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = val[0]
| ((len > 1) ? val[1] << 8 : 0x00)
| ((len > 2) ? val[2] << 16 : 0x00)
| ((len > 3) ? val[3] << 24 : 0x00);
dbg_write(dcc_data);
val += 4;
len -= 4;
}
}
void dbg_write_str(const char *msg)
{
long len;
unsigned long dcc_data;
for (len = 0; msg[len] && (len < 65536); len++) {
;
}
dbg_write(TARGET_REQ_DEBUGMSG_ASCII | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = msg[0]
| ((len > 1) ? msg[1] << 8 : 0x00)
| ((len > 2) ? msg[2] << 16 : 0x00)
| ((len > 3) ? msg[3] << 24 : 0x00);
dbg_write(dcc_data);
msg += 4;
len -= 4;
}
}
void dbg_write_char(char msg)
{
dbg_write(TARGET_REQ_DEBUGCHAR | ((msg & 0xff) << 16));
}
void dbg_write_hex32(const unsigned long val)
{
static const char hextab[] = {
'0', '1', '2', '3', '4', '5', '6', '7',
'8', '9', 'a', 'b', 'c', 'd', 'e', 'f'
};
for (int shift = 28; shift >= 0; shift -= 4) {
dbg_write_char(hextab[(val >> shift) & 0xf]);
}
}

View File

@ -1,36 +0,0 @@
/***************************************************************************
* Copyright (C) 2008 by Dominic Rath *
* Dominic.Rath@gmx.de *
* Copyright (C) 2008 by Spencer Oliver *
* spen@spen-soft.co.uk *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License, or *
* (at your option) any later version. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#ifndef DCC_STDIO_H
#define DCC_STDIO_H
void dbg_trace_point(unsigned long number);
void dbg_write_u32(const unsigned long *val, long len);
void dbg_write_u16(const unsigned short *val, long len);
void dbg_write_u8(const unsigned char *val, long len);
void dbg_write_str(const char *msg);
void dbg_write_char(char msg);
void dbg_write_hex32(const unsigned long val);
#endif /* DCC_STDIO_H */

View File

@ -70,11 +70,6 @@ ifndef TESTAPP
SRC += $(OPSYSTEM)/font_outlined8x14.c
SRC += $(OPSYSTEM)/font_outlined8x8.c
#ifeq ($(DEBUG), YES)
SRC += $(OPSYSTEM)/dcc_stdio.c
SRC += $(OPSYSTEM)/cm3_fault_handlers.c
#endif
## Misc library functions
SRC += $(FLIGHTLIB)/WorldMagModel.c
SRC += $(FLIGHTLIB)/auxmagsupport.c

View File

@ -1,90 +0,0 @@
/*
* cm3_fault_handlers.c
*
* Created on: Apr 24, 2011
* Author: msmith
*/
#include <stdint.h>
#include "inc/dcc_stdio.h"
#ifdef STM32F4XX
# include <stm32f4xx.h>
#endif
#ifdef STM32F2XX
# include <stm32f2xx.h>
#endif
#define FAULT_TRAMPOLINE(_vec) \
__attribute__((naked, no_instrument_function)) \
void \
_vec##_Handler(void) \
{ \
__asm(".syntax unified\n" \
"MOVS R0, #4 \n" \
"MOV R1, LR \n" \
"TST R0, R1 \n" \
"BEQ 1f \n" \
"MRS R0, PSP \n" \
"B " #_vec "_Handler2 \n" \
"1: \n" \
"MRS R0, MSP \n" \
"B " #_vec "_Handler2 \n" \
".syntax divided\n"); \
} \
struct hack
struct cm3_frame {
uint32_t r0;
uint32_t r1;
uint32_t r2;
uint32_t r3;
uint32_t r12;
uint32_t lr;
uint32_t pc;
uint32_t psr;
};
FAULT_TRAMPOLINE(HardFault);
FAULT_TRAMPOLINE(BusFault);
FAULT_TRAMPOLINE(UsageFault);
/* this is a hackaround to avoid an issue where dereferencing SCB seems to result in bad codegen and a link error */
#define SCB_REG(_reg) (*(uint32_t *)&(SCB->_reg))
void HardFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nHARD FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(HFSR));
dbg_write_char('\n');
for (;;) {
;
}
}
void BusFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nBUS FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(CFSR));
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(BFAR));
dbg_write_char('\n');
for (;;) {
;
}
}
void UsageFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nUSAGE FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(CFSR));
dbg_write_char('\n');
for (;;) {
;
}
}

View File

@ -1,149 +0,0 @@
/***************************************************************************
* Copyright (C) 2008 by Dominic Rath *
* Dominic.Rath@gmx.de *
* Copyright (C) 2008 by Spencer Oliver *
* spen@spen-soft.co.uk *
* Copyright (C) 2008 by Frederik Kriewtz *
* frederik@kriewitz.eu *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License, or *
* (at your option) any later version. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#include "inc/dcc_stdio.h"
#define TARGET_REQ_TRACEMSG 0x00
#define TARGET_REQ_DEBUGMSG_ASCII 0x01
#define TARGET_REQ_DEBUGMSG_HEXMSG(size) (0x01 | ((size & 0xff) << 8))
#define TARGET_REQ_DEBUGCHAR 0x02
/* we use the cortex_m3 DCRDR reg to simulate a arm7_9 dcc channel
* DCRDR[7:0] is used by target for status
* DCRDR[15:8] is used by target for write buffer
* DCRDR[23:16] is used for by host for status
* DCRDR[31:24] is used for by host for write buffer */
#define NVIC_DBG_DATA_R (*((volatile unsigned short *)0xE000EDF8))
#define BUSY 1
void dbg_write(unsigned long dcc_data)
{
int len = 4;
while (len--) {
/* wait for data ready */
while (NVIC_DBG_DATA_R & BUSY) {
;
}
/* write our data and set write flag - tell host there is data*/
NVIC_DBG_DATA_R = (unsigned short)(((dcc_data & 0xff) << 8) | BUSY);
dcc_data >>= 8;
}
}
void dbg_trace_point(unsigned long number)
{
dbg_write(TARGET_REQ_TRACEMSG | (number << 8));
}
void dbg_write_u32(const unsigned long *val, long len)
{
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(4) | ((len & 0xffff) << 16));
while (len > 0) {
dbg_write(*val);
val++;
len--;
}
}
void dbg_write_u16(const unsigned short *val, long len)
{
unsigned long dcc_data;
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(2) | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = val[0]
| ((len > 1) ? val[1] << 16 : 0x0000);
dbg_write(dcc_data);
val += 2;
len -= 2;
}
}
void dbg_write_u8(const unsigned char *val, long len)
{
unsigned long dcc_data;
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(1) | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = val[0]
| ((len > 1) ? val[1] << 8 : 0x00)
| ((len > 2) ? val[2] << 16 : 0x00)
| ((len > 3) ? val[3] << 24 : 0x00);
dbg_write(dcc_data);
val += 4;
len -= 4;
}
}
void dbg_write_str(const char *msg)
{
long len;
unsigned long dcc_data;
for (len = 0; msg[len] && (len < 65536); len++) {
;
}
dbg_write(TARGET_REQ_DEBUGMSG_ASCII | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = msg[0]
| ((len > 1) ? msg[1] << 8 : 0x00)
| ((len > 2) ? msg[2] << 16 : 0x00)
| ((len > 3) ? msg[3] << 24 : 0x00);
dbg_write(dcc_data);
msg += 4;
len -= 4;
}
}
void dbg_write_char(char msg)
{
dbg_write(TARGET_REQ_DEBUGCHAR | ((msg & 0xff) << 16));
}
void dbg_write_hex32(const unsigned long val)
{
static const char hextab[] = {
'0', '1', '2', '3', '4', '5', '6', '7',
'8', '9', 'a', 'b', 'c', 'd', 'e', 'f'
};
for (int shift = 28; shift >= 0; shift -= 4) {
dbg_write_char(hextab[(val >> shift) & 0xf]);
}
}

View File

@ -1,36 +0,0 @@
/***************************************************************************
* Copyright (C) 2008 by Dominic Rath *
* Dominic.Rath@gmx.de *
* Copyright (C) 2008 by Spencer Oliver *
* spen@spen-soft.co.uk *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License, or *
* (at your option) any later version. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#ifndef DCC_STDIO_H
#define DCC_STDIO_H
void dbg_trace_point(unsigned long number);
void dbg_write_u32(const unsigned long *val, long len);
void dbg_write_u16(const unsigned short *val, long len);
void dbg_write_u8(const unsigned char *val, long len);
void dbg_write_str(const char *msg);
void dbg_write_char(char msg);
void dbg_write_hex32(const unsigned long val);
#endif /* DCC_STDIO_H */

View File

@ -6,9 +6,8 @@ HW_TYPE := 0x01
CHIP := STM32F303xC
OPENOCD_JTAG_CONFIG := foss-jtag.revb.cfg
OPENOCD_CONFIG := stm32f1x.cfg
OPENOCD_CONFIG := stm32f3x.cfg
# Note: These must match the values in link_$(BOARD)_memory.ld
BL_BANK_BASE := 0x08000000 # Start of bootloader flash
BL_BANK_SIZE := 0x00004000 # Should include BD_INFO region

View File

@ -58,6 +58,7 @@ OPTMODULES += Battery
OPTMODULES += ComUsbBridge
OPTMODULES += UAVOMSPBridge
OPTMODULES += UAVOMavlinkBridge
OPTMODULES += UAVOFrSKYSensorHubBridge
SRC += $(FLIGHTLIB)/notification.c
@ -86,11 +87,6 @@ ifndef TESTAPP
SRC += $(PIOSCOMMON)/pios_flashfs_logfs.c
SRC += $(PIOSCOMMON)/pios_flash_jedec.c
#ifeq ($(DEBUG), YES)
SRC += $(OPSYSTEM)/dcc_stdio.c
SRC += $(OPSYSTEM)/cm3_fault_handlers.c
#endif
## Misc library functions
SRC += $(FLIGHTLIB)/instrumentation.c
SRC += $(FLIGHTLIB)/paths.c

View File

@ -1,93 +0,0 @@
/*
* cm3_fault_handlers.c
*
* Created on: Apr 24, 2011
* Author: msmith
*/
#include <stdint.h>
#include "inc/dcc_stdio.h"
#ifdef STM32F4XX
# include <stm32f4xx.h>
#endif
#ifdef STM32F3
# include <stm32f30x.h>
#endif
#ifdef STM32F2XX
# include <stm32f2xx.h>
#endif
#define FAULT_TRAMPOLINE(_vec) \
__attribute__((naked, no_instrument_function)) \
void \
_vec##_Handler(void) \
{ \
__asm(".syntax unified\n" \
"MOVS R0, #4 \n" \
"MOV R1, LR \n" \
"TST R0, R1 \n" \
"BEQ 1f \n" \
"MRS R0, PSP \n" \
"B " #_vec "_Handler2 \n" \
"1: \n" \
"MRS R0, MSP \n" \
"B " #_vec "_Handler2 \n" \
".syntax divided\n"); \
} \
struct hack
struct cm3_frame {
uint32_t r0;
uint32_t r1;
uint32_t r2;
uint32_t r3;
uint32_t r12;
uint32_t lr;
uint32_t pc;
uint32_t psr;
};
FAULT_TRAMPOLINE(HardFault);
FAULT_TRAMPOLINE(BusFault);
FAULT_TRAMPOLINE(UsageFault);
/* this is a hackaround to avoid an issue where dereferencing SCB seems to result in bad codegen and a link error */
#define SCB_REG(_reg) (*(uint32_t *)&(SCB->_reg))
void HardFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nHARD FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(HFSR));
dbg_write_char('\n');
for (;;) {
;
}
}
void BusFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nBUS FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(CFSR));
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(BFAR));
dbg_write_char('\n');
for (;;) {
;
}
}
void UsageFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nUSAGE FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(CFSR));
dbg_write_char('\n');
for (;;) {
;
}
}

View File

@ -1,149 +0,0 @@
/***************************************************************************
* Copyright (C) 2008 by Dominic Rath *
* Dominic.Rath@gmx.de *
* Copyright (C) 2008 by Spencer Oliver *
* spen@spen-soft.co.uk *
* Copyright (C) 2008 by Frederik Kriewtz *
* frederik@kriewitz.eu *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License, or *
* (at your option) any later version. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#include "inc/dcc_stdio.h"
#define TARGET_REQ_TRACEMSG 0x00
#define TARGET_REQ_DEBUGMSG_ASCII 0x01
#define TARGET_REQ_DEBUGMSG_HEXMSG(size) (0x01 | ((size & 0xff) << 8))
#define TARGET_REQ_DEBUGCHAR 0x02
/* we use the cortex_m3 DCRDR reg to simulate a arm7_9 dcc channel
* DCRDR[7:0] is used by target for status
* DCRDR[15:8] is used by target for write buffer
* DCRDR[23:16] is used for by host for status
* DCRDR[31:24] is used for by host for write buffer */
#define NVIC_DBG_DATA_R (*((volatile unsigned short *)0xE000EDF8))
#define BUSY 1
void dbg_write(unsigned long dcc_data)
{
int len = 4;
while (len--) {
/* wait for data ready */
while (NVIC_DBG_DATA_R & BUSY) {
;
}
/* write our data and set write flag - tell host there is data*/
NVIC_DBG_DATA_R = (unsigned short)(((dcc_data & 0xff) << 8) | BUSY);
dcc_data >>= 8;
}
}
void dbg_trace_point(unsigned long number)
{
dbg_write(TARGET_REQ_TRACEMSG | (number << 8));
}
void dbg_write_u32(const unsigned long *val, long len)
{
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(4) | ((len & 0xffff) << 16));
while (len > 0) {
dbg_write(*val);
val++;
len--;
}
}
void dbg_write_u16(const unsigned short *val, long len)
{
unsigned long dcc_data;
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(2) | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = val[0]
| ((len > 1) ? val[1] << 16 : 0x0000);
dbg_write(dcc_data);
val += 2;
len -= 2;
}
}
void dbg_write_u8(const unsigned char *val, long len)
{
unsigned long dcc_data;
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(1) | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = val[0]
| ((len > 1) ? val[1] << 8 : 0x00)
| ((len > 2) ? val[2] << 16 : 0x00)
| ((len > 3) ? val[3] << 24 : 0x00);
dbg_write(dcc_data);
val += 4;
len -= 4;
}
}
void dbg_write_str(const char *msg)
{
long len;
unsigned long dcc_data;
for (len = 0; msg[len] && (len < 65536); len++) {
;
}
dbg_write(TARGET_REQ_DEBUGMSG_ASCII | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = msg[0]
| ((len > 1) ? msg[1] << 8 : 0x00)
| ((len > 2) ? msg[2] << 16 : 0x00)
| ((len > 3) ? msg[3] << 24 : 0x00);
dbg_write(dcc_data);
msg += 4;
len -= 4;
}
}
void dbg_write_char(char msg)
{
dbg_write(TARGET_REQ_DEBUGCHAR | ((msg & 0xff) << 16));
}
void dbg_write_hex32(const unsigned long val)
{
static const char hextab[] = {
'0', '1', '2', '3', '4', '5', '6', '7',
'8', '9', 'a', 'b', 'c', 'd', 'e', 'f'
};
for (int shift = 28; shift >= 0; shift -= 4) {
dbg_write_char(hextab[(val >> shift) & 0xf]);
}
}

View File

@ -1,36 +0,0 @@
/***************************************************************************
* Copyright (C) 2008 by Dominic Rath *
* Dominic.Rath@gmx.de *
* Copyright (C) 2008 by Spencer Oliver *
* spen@spen-soft.co.uk *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License, or *
* (at your option) any later version. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#ifndef DCC_STDIO_H
#define DCC_STDIO_H
void dbg_trace_point(unsigned long number);
void dbg_write_u32(const unsigned long *val, long len);
void dbg_write_u16(const unsigned short *val, long len);
void dbg_write_u8(const unsigned char *val, long len);
void dbg_write_str(const char *msg);
void dbg_write_char(char msg);
void dbg_write_hex32(const unsigned long val);
#endif /* DCC_STDIO_H */

View File

@ -88,11 +88,6 @@ ifndef TESTAPP
SRC += $(PIOSCOMMON)/pios_flashfs_logfs.c
SRC += $(PIOSCOMMON)/pios_flash_jedec.c
#ifeq ($(DEBUG), YES)
SRC += $(OPSYSTEM)/dcc_stdio.c
SRC += $(OPSYSTEM)/cm3_fault_handlers.c
#endif
## Misc library functions
SRC += $(FLIGHTLIB)/paths.c
SRC += $(FLIGHTLIB)/plans.c

View File

@ -1,90 +0,0 @@
/*
* cm3_fault_handlers.c
*
* Created on: Apr 24, 2011
* Author: msmith
*/
#include <stdint.h>
#include "inc/dcc_stdio.h"
#ifdef STM32F4XX
# include <stm32f4xx.h>
#endif
#ifdef STM32F2XX
# include <stm32f2xx.h>
#endif
#define FAULT_TRAMPOLINE(_vec) \
__attribute__((naked, no_instrument_function)) \
void \
_vec##_Handler(void) \
{ \
__asm(".syntax unified\n" \
"MOVS R0, #4 \n" \
"MOV R1, LR \n" \
"TST R0, R1 \n" \
"BEQ 1f \n" \
"MRS R0, PSP \n" \
"B " #_vec "_Handler2 \n" \
"1: \n" \
"MRS R0, MSP \n" \
"B " #_vec "_Handler2 \n" \
".syntax divided\n"); \
} \
struct hack
struct cm3_frame {
uint32_t r0;
uint32_t r1;
uint32_t r2;
uint32_t r3;
uint32_t r12;
uint32_t lr;
uint32_t pc;
uint32_t psr;
};
FAULT_TRAMPOLINE(HardFault);
FAULT_TRAMPOLINE(BusFault);
FAULT_TRAMPOLINE(UsageFault);
/* this is a hackaround to avoid an issue where dereferencing SCB seems to result in bad codegen and a link error */
#define SCB_REG(_reg) (*(uint32_t *)&(SCB->_reg))
void HardFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nHARD FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(HFSR));
dbg_write_char('\n');
for (;;) {
;
}
}
void BusFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nBUS FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(CFSR));
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(BFAR));
dbg_write_char('\n');
for (;;) {
;
}
}
void UsageFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nUSAGE FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(CFSR));
dbg_write_char('\n');
for (;;) {
;
}
}

View File

@ -1,149 +0,0 @@
/***************************************************************************
* Copyright (C) 2008 by Dominic Rath *
* Dominic.Rath@gmx.de *
* Copyright (C) 2008 by Spencer Oliver *
* spen@spen-soft.co.uk *
* Copyright (C) 2008 by Frederik Kriewtz *
* frederik@kriewitz.eu *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License, or *
* (at your option) any later version. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#include "inc/dcc_stdio.h"
#define TARGET_REQ_TRACEMSG 0x00
#define TARGET_REQ_DEBUGMSG_ASCII 0x01
#define TARGET_REQ_DEBUGMSG_HEXMSG(size) (0x01 | ((size & 0xff) << 8))
#define TARGET_REQ_DEBUGCHAR 0x02
/* we use the cortex_m3 DCRDR reg to simulate a arm7_9 dcc channel
* DCRDR[7:0] is used by target for status
* DCRDR[15:8] is used by target for write buffer
* DCRDR[23:16] is used for by host for status
* DCRDR[31:24] is used for by host for write buffer */
#define NVIC_DBG_DATA_R (*((volatile unsigned short *)0xE000EDF8))
#define BUSY 1
void dbg_write(unsigned long dcc_data)
{
int len = 4;
while (len--) {
/* wait for data ready */
while (NVIC_DBG_DATA_R & BUSY) {
;
}
/* write our data and set write flag - tell host there is data*/
NVIC_DBG_DATA_R = (unsigned short)(((dcc_data & 0xff) << 8) | BUSY);
dcc_data >>= 8;
}
}
void dbg_trace_point(unsigned long number)
{
dbg_write(TARGET_REQ_TRACEMSG | (number << 8));
}
void dbg_write_u32(const unsigned long *val, long len)
{
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(4) | ((len & 0xffff) << 16));
while (len > 0) {
dbg_write(*val);
val++;
len--;
}
}
void dbg_write_u16(const unsigned short *val, long len)
{
unsigned long dcc_data;
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(2) | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = val[0]
| ((len > 1) ? val[1] << 16 : 0x0000);
dbg_write(dcc_data);
val += 2;
len -= 2;
}
}
void dbg_write_u8(const unsigned char *val, long len)
{
unsigned long dcc_data;
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(1) | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = val[0]
| ((len > 1) ? val[1] << 8 : 0x00)
| ((len > 2) ? val[2] << 16 : 0x00)
| ((len > 3) ? val[3] << 24 : 0x00);
dbg_write(dcc_data);
val += 4;
len -= 4;
}
}
void dbg_write_str(const char *msg)
{
long len;
unsigned long dcc_data;
for (len = 0; msg[len] && (len < 65536); len++) {
;
}
dbg_write(TARGET_REQ_DEBUGMSG_ASCII | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = msg[0]
| ((len > 1) ? msg[1] << 8 : 0x00)
| ((len > 2) ? msg[2] << 16 : 0x00)
| ((len > 3) ? msg[3] << 24 : 0x00);
dbg_write(dcc_data);
msg += 4;
len -= 4;
}
}
void dbg_write_char(char msg)
{
dbg_write(TARGET_REQ_DEBUGCHAR | ((msg & 0xff) << 16));
}
void dbg_write_hex32(const unsigned long val)
{
static const char hextab[] = {
'0', '1', '2', '3', '4', '5', '6', '7',
'8', '9', 'a', 'b', 'c', 'd', 'e', 'f'
};
for (int shift = 28; shift >= 0; shift -= 4) {
dbg_write_char(hextab[(val >> shift) & 0xf]);
}
}

View File

@ -1,36 +0,0 @@
/***************************************************************************
* Copyright (C) 2008 by Dominic Rath *
* Dominic.Rath@gmx.de *
* Copyright (C) 2008 by Spencer Oliver *
* spen@spen-soft.co.uk *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License, or *
* (at your option) any later version. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#ifndef DCC_STDIO_H
#define DCC_STDIO_H
void dbg_trace_point(unsigned long number);
void dbg_write_u32(const unsigned long *val, long len);
void dbg_write_u16(const unsigned short *val, long len);
void dbg_write_u8(const unsigned char *val, long len);
void dbg_write_str(const char *msg);
void dbg_write_char(char msg);
void dbg_write_hex32(const unsigned long val);
#endif /* DCC_STDIO_H */

View File

@ -86,11 +86,6 @@ ifndef TESTAPP
SRC += $(PIOSCOMMON)/pios_flash_eeprom.c
SRC += $(PIOSCOMMON)/pios_flashfs_objlist.c
#ifeq ($(DEBUG), YES)
SRC += $(OPSYSTEM)/dcc_stdio.c
SRC += $(OPSYSTEM)/cm3_fault_handlers.c
#endif
## Misc library functions
SRC += $(FLIGHTLIB)/paths.c
SRC += $(FLIGHTLIB)/plans.c

View File

@ -1,90 +0,0 @@
/*
* cm3_fault_handlers.c
*
* Created on: Apr 24, 2011
* Author: msmith
*/
#include <stdint.h>
#include "inc/dcc_stdio.h"
#ifdef STM32F4XX
# include <stm32f4xx.h>
#endif
#ifdef STM32F2XX
# include <stm32f2xx.h>
#endif
#define FAULT_TRAMPOLINE(_vec) \
__attribute__((naked, no_instrument_function)) \
void \
_vec##_Handler(void) \
{ \
__asm(".syntax unified\n" \
"MOVS R0, #4 \n" \
"MOV R1, LR \n" \
"TST R0, R1 \n" \
"BEQ 1f \n" \
"MRS R0, PSP \n" \
"B " #_vec "_Handler2 \n" \
"1: \n" \
"MRS R0, MSP \n" \
"B " #_vec "_Handler2 \n" \
".syntax divided\n"); \
} \
struct hack
struct cm3_frame {
uint32_t r0;
uint32_t r1;
uint32_t r2;
uint32_t r3;
uint32_t r12;
uint32_t lr;
uint32_t pc;
uint32_t psr;
};
FAULT_TRAMPOLINE(HardFault);
FAULT_TRAMPOLINE(BusFault);
FAULT_TRAMPOLINE(UsageFault);
/* this is a hackaround to avoid an issue where dereferencing SCB seems to result in bad codegen and a link error */
#define SCB_REG(_reg) (*(uint32_t *)&(SCB->_reg))
void HardFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nHARD FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(HFSR));
dbg_write_char('\n');
for (;;) {
;
}
}
void BusFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nBUS FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(CFSR));
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(BFAR));
dbg_write_char('\n');
for (;;) {
;
}
}
void UsageFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nUSAGE FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(CFSR));
dbg_write_char('\n');
for (;;) {
;
}
}

View File

@ -1,149 +0,0 @@
/***************************************************************************
* Copyright (C) 2008 by Dominic Rath *
* Dominic.Rath@gmx.de *
* Copyright (C) 2008 by Spencer Oliver *
* spen@spen-soft.co.uk *
* Copyright (C) 2008 by Frederik Kriewtz *
* frederik@kriewitz.eu *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License, or *
* (at your option) any later version. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#include "inc/dcc_stdio.h"
#define TARGET_REQ_TRACEMSG 0x00
#define TARGET_REQ_DEBUGMSG_ASCII 0x01
#define TARGET_REQ_DEBUGMSG_HEXMSG(size) (0x01 | ((size & 0xff) << 8))
#define TARGET_REQ_DEBUGCHAR 0x02
/* we use the cortex_m3 DCRDR reg to simulate a arm7_9 dcc channel
* DCRDR[7:0] is used by target for status
* DCRDR[15:8] is used by target for write buffer
* DCRDR[23:16] is used for by host for status
* DCRDR[31:24] is used for by host for write buffer */
#define NVIC_DBG_DATA_R (*((volatile unsigned short *)0xE000EDF8))
#define BUSY 1
void dbg_write(unsigned long dcc_data)
{
int len = 4;
while (len--) {
/* wait for data ready */
while (NVIC_DBG_DATA_R & BUSY) {
;
}
/* write our data and set write flag - tell host there is data*/
NVIC_DBG_DATA_R = (unsigned short)(((dcc_data & 0xff) << 8) | BUSY);
dcc_data >>= 8;
}
}
void dbg_trace_point(unsigned long number)
{
dbg_write(TARGET_REQ_TRACEMSG | (number << 8));
}
void dbg_write_u32(const unsigned long *val, long len)
{
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(4) | ((len & 0xffff) << 16));
while (len > 0) {
dbg_write(*val);
val++;
len--;
}
}
void dbg_write_u16(const unsigned short *val, long len)
{
unsigned long dcc_data;
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(2) | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = val[0]
| ((len > 1) ? val[1] << 16 : 0x0000);
dbg_write(dcc_data);
val += 2;
len -= 2;
}
}
void dbg_write_u8(const unsigned char *val, long len)
{
unsigned long dcc_data;
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(1) | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = val[0]
| ((len > 1) ? val[1] << 8 : 0x00)
| ((len > 2) ? val[2] << 16 : 0x00)
| ((len > 3) ? val[3] << 24 : 0x00);
dbg_write(dcc_data);
val += 4;
len -= 4;
}
}
void dbg_write_str(const char *msg)
{
long len;
unsigned long dcc_data;
for (len = 0; msg[len] && (len < 65536); len++) {
;
}
dbg_write(TARGET_REQ_DEBUGMSG_ASCII | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = msg[0]
| ((len > 1) ? msg[1] << 8 : 0x00)
| ((len > 2) ? msg[2] << 16 : 0x00)
| ((len > 3) ? msg[3] << 24 : 0x00);
dbg_write(dcc_data);
msg += 4;
len -= 4;
}
}
void dbg_write_char(char msg)
{
dbg_write(TARGET_REQ_DEBUGCHAR | ((msg & 0xff) << 16));
}
void dbg_write_hex32(const unsigned long val)
{
static const char hextab[] = {
'0', '1', '2', '3', '4', '5', '6', '7',
'8', '9', 'a', 'b', 'c', 'd', 'e', 'f'
};
for (int shift = 28; shift >= 0; shift -= 4) {
dbg_write_char(hextab[(val >> shift) & 0xf]);
}
}

View File

@ -1,36 +0,0 @@
/***************************************************************************
* Copyright (C) 2008 by Dominic Rath *
* Dominic.Rath@gmx.de *
* Copyright (C) 2008 by Spencer Oliver *
* spen@spen-soft.co.uk *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License, or *
* (at your option) any later version. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#ifndef DCC_STDIO_H
#define DCC_STDIO_H
void dbg_trace_point(unsigned long number);
void dbg_write_u32(const unsigned long *val, long len);
void dbg_write_u16(const unsigned short *val, long len);
void dbg_write_u8(const unsigned char *val, long len);
void dbg_write_str(const char *msg);
void dbg_write_char(char msg);
void dbg_write_hex32(const unsigned long val);
#endif /* DCC_STDIO_H */

View File

@ -83,11 +83,6 @@ ifndef TESTAPP
SRC += $(PIOSCOMMON)/pios_flashfs_logfs.c
SRC += $(PIOSCOMMON)/pios_flash_jedec.c
#ifeq ($(DEBUG), YES)
SRC += $(OPSYSTEM)/dcc_stdio.c
SRC += $(OPSYSTEM)/cm3_fault_handlers.c
#endif
## Misc library functions
SRC += $(FLIGHTLIB)/paths.c
SRC += $(FLIGHTLIB)/plans.c

View File

@ -1,90 +0,0 @@
/*
* cm3_fault_handlers.c
*
* Created on: Apr 24, 2011
* Author: msmith
*/
#include <stdint.h>
#include "inc/dcc_stdio.h"
#ifdef STM32F4XX
# include <stm32f4xx.h>
#endif
#ifdef STM32F2XX
# include <stm32f2xx.h>
#endif
#define FAULT_TRAMPOLINE(_vec) \
__attribute__((naked, no_instrument_function)) \
void \
_vec##_Handler(void) \
{ \
__asm(".syntax unified\n" \
"MOVS R0, #4 \n" \
"MOV R1, LR \n" \
"TST R0, R1 \n" \
"BEQ 1f \n" \
"MRS R0, PSP \n" \
"B " #_vec "_Handler2 \n" \
"1: \n" \
"MRS R0, MSP \n" \
"B " #_vec "_Handler2 \n" \
".syntax divided\n"); \
} \
struct hack
struct cm3_frame {
uint32_t r0;
uint32_t r1;
uint32_t r2;
uint32_t r3;
uint32_t r12;
uint32_t lr;
uint32_t pc;
uint32_t psr;
};
FAULT_TRAMPOLINE(HardFault);
FAULT_TRAMPOLINE(BusFault);
FAULT_TRAMPOLINE(UsageFault);
/* this is a hackaround to avoid an issue where dereferencing SCB seems to result in bad codegen and a link error */
#define SCB_REG(_reg) (*(uint32_t *)&(SCB->_reg))
void HardFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nHARD FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(HFSR));
dbg_write_char('\n');
for (;;) {
;
}
}
void BusFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nBUS FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(CFSR));
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(BFAR));
dbg_write_char('\n');
for (;;) {
;
}
}
void UsageFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nUSAGE FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(CFSR));
dbg_write_char('\n');
for (;;) {
;
}
}

View File

@ -1,149 +0,0 @@
/***************************************************************************
* Copyright (C) 2008 by Dominic Rath *
* Dominic.Rath@gmx.de *
* Copyright (C) 2008 by Spencer Oliver *
* spen@spen-soft.co.uk *
* Copyright (C) 2008 by Frederik Kriewtz *
* frederik@kriewitz.eu *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License, or *
* (at your option) any later version. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#include "inc/dcc_stdio.h"
#define TARGET_REQ_TRACEMSG 0x00
#define TARGET_REQ_DEBUGMSG_ASCII 0x01
#define TARGET_REQ_DEBUGMSG_HEXMSG(size) (0x01 | ((size & 0xff) << 8))
#define TARGET_REQ_DEBUGCHAR 0x02
/* we use the cortex_m3 DCRDR reg to simulate a arm7_9 dcc channel
* DCRDR[7:0] is used by target for status
* DCRDR[15:8] is used by target for write buffer
* DCRDR[23:16] is used for by host for status
* DCRDR[31:24] is used for by host for write buffer */
#define NVIC_DBG_DATA_R (*((volatile unsigned short *)0xE000EDF8))
#define BUSY 1
void dbg_write(unsigned long dcc_data)
{
int len = 4;
while (len--) {
/* wait for data ready */
while (NVIC_DBG_DATA_R & BUSY) {
;
}
/* write our data and set write flag - tell host there is data*/
NVIC_DBG_DATA_R = (unsigned short)(((dcc_data & 0xff) << 8) | BUSY);
dcc_data >>= 8;
}
}
void dbg_trace_point(unsigned long number)
{
dbg_write(TARGET_REQ_TRACEMSG | (number << 8));
}
void dbg_write_u32(const unsigned long *val, long len)
{
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(4) | ((len & 0xffff) << 16));
while (len > 0) {
dbg_write(*val);
val++;
len--;
}
}
void dbg_write_u16(const unsigned short *val, long len)
{
unsigned long dcc_data;
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(2) | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = val[0]
| ((len > 1) ? val[1] << 16 : 0x0000);
dbg_write(dcc_data);
val += 2;
len -= 2;
}
}
void dbg_write_u8(const unsigned char *val, long len)
{
unsigned long dcc_data;
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(1) | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = val[0]
| ((len > 1) ? val[1] << 8 : 0x00)
| ((len > 2) ? val[2] << 16 : 0x00)
| ((len > 3) ? val[3] << 24 : 0x00);
dbg_write(dcc_data);
val += 4;
len -= 4;
}
}
void dbg_write_str(const char *msg)
{
long len;
unsigned long dcc_data;
for (len = 0; msg[len] && (len < 65536); len++) {
;
}
dbg_write(TARGET_REQ_DEBUGMSG_ASCII | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = msg[0]
| ((len > 1) ? msg[1] << 8 : 0x00)
| ((len > 2) ? msg[2] << 16 : 0x00)
| ((len > 3) ? msg[3] << 24 : 0x00);
dbg_write(dcc_data);
msg += 4;
len -= 4;
}
}
void dbg_write_char(char msg)
{
dbg_write(TARGET_REQ_DEBUGCHAR | ((msg & 0xff) << 16));
}
void dbg_write_hex32(const unsigned long val)
{
static const char hextab[] = {
'0', '1', '2', '3', '4', '5', '6', '7',
'8', '9', 'a', 'b', 'c', 'd', 'e', 'f'
};
for (int shift = 28; shift >= 0; shift -= 4) {
dbg_write_char(hextab[(val >> shift) & 0xf]);
}
}

View File

@ -1,36 +0,0 @@
/***************************************************************************
* Copyright (C) 2008 by Dominic Rath *
* Dominic.Rath@gmx.de *
* Copyright (C) 2008 by Spencer Oliver *
* spen@spen-soft.co.uk *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License, or *
* (at your option) any later version. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#ifndef DCC_STDIO_H
#define DCC_STDIO_H
void dbg_trace_point(unsigned long number);
void dbg_write_u32(const unsigned long *val, long len);
void dbg_write_u16(const unsigned short *val, long len);
void dbg_write_u8(const unsigned char *val, long len);
void dbg_write_str(const char *msg);
void dbg_write_char(char msg);
void dbg_write_hex32(const unsigned long val);
#endif /* DCC_STDIO_H */

View File

@ -1,36 +0,0 @@
/***************************************************************************
* Copyright (C) 2008 by Dominic Rath *
* Dominic.Rath@gmx.de *
* Copyright (C) 2008 by Spencer Oliver *
* spen@spen-soft.co.uk *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License, or *
* (at your option) any later version. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#ifndef DCC_STDIO_H
#define DCC_STDIO_H
void dbg_trace_point(unsigned long number);
void dbg_write_u32(const unsigned long *val, long len);
void dbg_write_u16(const unsigned short *val, long len);
void dbg_write_u8(const unsigned char *val, long len);
void dbg_write_str(const char *msg);
void dbg_write_char(char msg);
void dbg_write_hex32(const unsigned long val);
#endif /* DCC_STDIO_H */

View File

@ -87,11 +87,6 @@ ifndef TESTAPP
SRC += $(PIOSCOMMON)/pios_flashfs_logfs.c
SRC += $(PIOSCOMMON)/pios_flash_jedec.c
#ifeq ($(DEBUG), YES)
SRC += $(OPSYSTEM)/dcc_stdio.c
SRC += $(OPSYSTEM)/cm3_fault_handlers.c
#endif
## Misc library functions
SRC += $(FLIGHTLIB)/paths.c
SRC += $(FLIGHTLIB)/plans.c

View File

@ -1,90 +0,0 @@
/*
* cm3_fault_handlers.c
*
* Created on: Apr 24, 2011
* Author: msmith
*/
#include <stdint.h>
#include "inc/dcc_stdio.h"
#ifdef STM32F4XX
# include <stm32f4xx.h>
#endif
#ifdef STM32F2XX
# include <stm32f2xx.h>
#endif
#define FAULT_TRAMPOLINE(_vec) \
__attribute__((naked, no_instrument_function)) \
void \
_vec##_Handler(void) \
{ \
__asm(".syntax unified\n" \
"MOVS R0, #4 \n" \
"MOV R1, LR \n" \
"TST R0, R1 \n" \
"BEQ 1f \n" \
"MRS R0, PSP \n" \
"B " #_vec "_Handler2 \n" \
"1: \n" \
"MRS R0, MSP \n" \
"B " #_vec "_Handler2 \n" \
".syntax divided\n"); \
} \
struct hack
struct cm3_frame {
uint32_t r0;
uint32_t r1;
uint32_t r2;
uint32_t r3;
uint32_t r12;
uint32_t lr;
uint32_t pc;
uint32_t psr;
};
FAULT_TRAMPOLINE(HardFault);
FAULT_TRAMPOLINE(BusFault);
FAULT_TRAMPOLINE(UsageFault);
/* this is a hackaround to avoid an issue where dereferencing SCB seems to result in bad codegen and a link error */
#define SCB_REG(_reg) (*(uint32_t *)&(SCB->_reg))
void HardFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nHARD FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(HFSR));
dbg_write_char('\n');
for (;;) {
;
}
}
void BusFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nBUS FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(CFSR));
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(BFAR));
dbg_write_char('\n');
for (;;) {
;
}
}
void UsageFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nUSAGE FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(CFSR));
dbg_write_char('\n');
for (;;) {
;
}
}

View File

@ -1,149 +0,0 @@
/***************************************************************************
* Copyright (C) 2008 by Dominic Rath *
* Dominic.Rath@gmx.de *
* Copyright (C) 2008 by Spencer Oliver *
* spen@spen-soft.co.uk *
* Copyright (C) 2008 by Frederik Kriewtz *
* frederik@kriewitz.eu *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License, or *
* (at your option) any later version. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#include "inc/dcc_stdio.h"
#define TARGET_REQ_TRACEMSG 0x00
#define TARGET_REQ_DEBUGMSG_ASCII 0x01
#define TARGET_REQ_DEBUGMSG_HEXMSG(size) (0x01 | ((size & 0xff) << 8))
#define TARGET_REQ_DEBUGCHAR 0x02
/* we use the cortex_m3 DCRDR reg to simulate a arm7_9 dcc channel
* DCRDR[7:0] is used by target for status
* DCRDR[15:8] is used by target for write buffer
* DCRDR[23:16] is used for by host for status
* DCRDR[31:24] is used for by host for write buffer */
#define NVIC_DBG_DATA_R (*((volatile unsigned short *)0xE000EDF8))
#define BUSY 1
void dbg_write(unsigned long dcc_data)
{
int len = 4;
while (len--) {
/* wait for data ready */
while (NVIC_DBG_DATA_R & BUSY) {
;
}
/* write our data and set write flag - tell host there is data*/
NVIC_DBG_DATA_R = (unsigned short)(((dcc_data & 0xff) << 8) | BUSY);
dcc_data >>= 8;
}
}
void dbg_trace_point(unsigned long number)
{
dbg_write(TARGET_REQ_TRACEMSG | (number << 8));
}
void dbg_write_u32(const unsigned long *val, long len)
{
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(4) | ((len & 0xffff) << 16));
while (len > 0) {
dbg_write(*val);
val++;
len--;
}
}
void dbg_write_u16(const unsigned short *val, long len)
{
unsigned long dcc_data;
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(2) | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = val[0]
| ((len > 1) ? val[1] << 16 : 0x0000);
dbg_write(dcc_data);
val += 2;
len -= 2;
}
}
void dbg_write_u8(const unsigned char *val, long len)
{
unsigned long dcc_data;
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(1) | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = val[0]
| ((len > 1) ? val[1] << 8 : 0x00)
| ((len > 2) ? val[2] << 16 : 0x00)
| ((len > 3) ? val[3] << 24 : 0x00);
dbg_write(dcc_data);
val += 4;
len -= 4;
}
}
void dbg_write_str(const char *msg)
{
long len;
unsigned long dcc_data;
for (len = 0; msg[len] && (len < 65536); len++) {
;
}
dbg_write(TARGET_REQ_DEBUGMSG_ASCII | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = msg[0]
| ((len > 1) ? msg[1] << 8 : 0x00)
| ((len > 2) ? msg[2] << 16 : 0x00)
| ((len > 3) ? msg[3] << 24 : 0x00);
dbg_write(dcc_data);
msg += 4;
len -= 4;
}
}
void dbg_write_char(char msg)
{
dbg_write(TARGET_REQ_DEBUGCHAR | ((msg & 0xff) << 16));
}
void dbg_write_hex32(const unsigned long val)
{
static const char hextab[] = {
'0', '1', '2', '3', '4', '5', '6', '7',
'8', '9', 'a', 'b', 'c', 'd', 'e', 'f'
};
for (int shift = 28; shift >= 0; shift -= 4) {
dbg_write_char(hextab[(val >> shift) & 0xf]);
}
}

View File

@ -1,36 +0,0 @@
/***************************************************************************
* Copyright (C) 2008 by Dominic Rath *
* Dominic.Rath@gmx.de *
* Copyright (C) 2008 by Spencer Oliver *
* spen@spen-soft.co.uk *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License, or *
* (at your option) any later version. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#ifndef DCC_STDIO_H
#define DCC_STDIO_H
void dbg_trace_point(unsigned long number);
void dbg_write_u32(const unsigned long *val, long len);
void dbg_write_u16(const unsigned short *val, long len);
void dbg_write_u8(const unsigned char *val, long len);
void dbg_write_str(const char *msg);
void dbg_write_char(char msg);
void dbg_write_hex32(const unsigned long val);
#endif /* DCC_STDIO_H */

View File

@ -25,7 +25,7 @@ endif
include ../board-info.mk
include $(FLIGHT_ROOT_DIR)/make/firmware-defs.mk
# REVO C++ support
# C++ support
USE_CXX = YES
# ARM DSP library
@ -60,6 +60,7 @@ OPTMODULES += Battery
OPTMODULES += ComUsbBridge
OPTMODULES += UAVOMSPBridge
OPTMODULES += UAVOMavlinkBridge
OPTMODULES += UAVOFrSKYSensorHubBridge
SRC += $(FLIGHTLIB)/notification.c
@ -87,11 +88,6 @@ ifndef TESTAPP
SRC += $(PIOSCOMMON)/pios_flashfs_logfs.c
SRC += $(PIOSCOMMON)/pios_flash_jedec.c
#ifeq ($(DEBUG), YES)
SRC += $(OPSYSTEM)/dcc_stdio.c
SRC += $(OPSYSTEM)/cm3_fault_handlers.c
#endif
## Misc library functions
SRC += $(FLIGHTLIB)/instrumentation.c
SRC += $(FLIGHTLIB)/paths.c

View File

@ -1,93 +0,0 @@
/*
* cm3_fault_handlers.c
*
* Created on: Apr 24, 2011
* Author: msmith
*/
#include <stdint.h>
#include "inc/dcc_stdio.h"
#ifdef STM32F4XX
# include <stm32f4xx.h>
#endif
#ifdef STM32F3
# include <stm32f30x.h>
#endif
#ifdef STM32F2XX
# include <stm32f2xx.h>
#endif
#define FAULT_TRAMPOLINE(_vec) \
__attribute__((naked, no_instrument_function)) \
void \
_vec##_Handler(void) \
{ \
__asm(".syntax unified\n" \
"MOVS R0, #4 \n" \
"MOV R1, LR \n" \
"TST R0, R1 \n" \
"BEQ 1f \n" \
"MRS R0, PSP \n" \
"B " #_vec "_Handler2 \n" \
"1: \n" \
"MRS R0, MSP \n" \
"B " #_vec "_Handler2 \n" \
".syntax divided\n"); \
} \
struct hack
struct cm3_frame {
uint32_t r0;
uint32_t r1;
uint32_t r2;
uint32_t r3;
uint32_t r12;
uint32_t lr;
uint32_t pc;
uint32_t psr;
};
FAULT_TRAMPOLINE(HardFault);
FAULT_TRAMPOLINE(BusFault);
FAULT_TRAMPOLINE(UsageFault);
/* this is a hackaround to avoid an issue where dereferencing SCB seems to result in bad codegen and a link error */
#define SCB_REG(_reg) (*(uint32_t *)&(SCB->_reg))
void HardFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nHARD FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(HFSR));
dbg_write_char('\n');
for (;;) {
;
}
}
void BusFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nBUS FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(CFSR));
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(BFAR));
dbg_write_char('\n');
for (;;) {
;
}
}
void UsageFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nUSAGE FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(CFSR));
dbg_write_char('\n');
for (;;) {
;
}
}

View File

@ -1,149 +0,0 @@
/***************************************************************************
* Copyright (C) 2008 by Dominic Rath *
* Dominic.Rath@gmx.de *
* Copyright (C) 2008 by Spencer Oliver *
* spen@spen-soft.co.uk *
* Copyright (C) 2008 by Frederik Kriewtz *
* frederik@kriewitz.eu *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License, or *
* (at your option) any later version. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#include "inc/dcc_stdio.h"
#define TARGET_REQ_TRACEMSG 0x00
#define TARGET_REQ_DEBUGMSG_ASCII 0x01
#define TARGET_REQ_DEBUGMSG_HEXMSG(size) (0x01 | ((size & 0xff) << 8))
#define TARGET_REQ_DEBUGCHAR 0x02
/* we use the cortex_m3 DCRDR reg to simulate a arm7_9 dcc channel
* DCRDR[7:0] is used by target for status
* DCRDR[15:8] is used by target for write buffer
* DCRDR[23:16] is used for by host for status
* DCRDR[31:24] is used for by host for write buffer */
#define NVIC_DBG_DATA_R (*((volatile unsigned short *)0xE000EDF8))
#define BUSY 1
void dbg_write(unsigned long dcc_data)
{
int len = 4;
while (len--) {
/* wait for data ready */
while (NVIC_DBG_DATA_R & BUSY) {
;
}
/* write our data and set write flag - tell host there is data*/
NVIC_DBG_DATA_R = (unsigned short)(((dcc_data & 0xff) << 8) | BUSY);
dcc_data >>= 8;
}
}
void dbg_trace_point(unsigned long number)
{
dbg_write(TARGET_REQ_TRACEMSG | (number << 8));
}
void dbg_write_u32(const unsigned long *val, long len)
{
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(4) | ((len & 0xffff) << 16));
while (len > 0) {
dbg_write(*val);
val++;
len--;
}
}
void dbg_write_u16(const unsigned short *val, long len)
{
unsigned long dcc_data;
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(2) | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = val[0]
| ((len > 1) ? val[1] << 16 : 0x0000);
dbg_write(dcc_data);
val += 2;
len -= 2;
}
}
void dbg_write_u8(const unsigned char *val, long len)
{
unsigned long dcc_data;
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(1) | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = val[0]
| ((len > 1) ? val[1] << 8 : 0x00)
| ((len > 2) ? val[2] << 16 : 0x00)
| ((len > 3) ? val[3] << 24 : 0x00);
dbg_write(dcc_data);
val += 4;
len -= 4;
}
}
void dbg_write_str(const char *msg)
{
long len;
unsigned long dcc_data;
for (len = 0; msg[len] && (len < 65536); len++) {
;
}
dbg_write(TARGET_REQ_DEBUGMSG_ASCII | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = msg[0]
| ((len > 1) ? msg[1] << 8 : 0x00)
| ((len > 2) ? msg[2] << 16 : 0x00)
| ((len > 3) ? msg[3] << 24 : 0x00);
dbg_write(dcc_data);
msg += 4;
len -= 4;
}
}
void dbg_write_char(char msg)
{
dbg_write(TARGET_REQ_DEBUGCHAR | ((msg & 0xff) << 16));
}
void dbg_write_hex32(const unsigned long val)
{
static const char hextab[] = {
'0', '1', '2', '3', '4', '5', '6', '7',
'8', '9', 'a', 'b', 'c', 'd', 'e', 'f'
};
for (int shift = 28; shift >= 0; shift -= 4) {
dbg_write_char(hextab[(val >> shift) & 0xf]);
}
}

View File

@ -1,36 +0,0 @@
/***************************************************************************
* Copyright (C) 2008 by Dominic Rath *
* Dominic.Rath@gmx.de *
* Copyright (C) 2008 by Spencer Oliver *
* spen@spen-soft.co.uk *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License, or *
* (at your option) any later version. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#ifndef DCC_STDIO_H
#define DCC_STDIO_H
void dbg_trace_point(unsigned long number);
void dbg_write_u32(const unsigned long *val, long len);
void dbg_write_u16(const unsigned short *val, long len);
void dbg_write_u8(const unsigned char *val, long len);
void dbg_write_str(const char *msg);
void dbg_write_char(char msg);
void dbg_write_hex32(const unsigned long val);
#endif /* DCC_STDIO_H */

View File

@ -3,17 +3,11 @@ BOARD_REVISION := 0x02
BOOTLOADER_VERSION := 0x04
HW_TYPE := 0x01
MCU := cortex-m4
PIOS_DEVLIB := $(PIOS)/stm32f30x
CHIP := STM32F303xC
BOARD := STM32F303CCT_SPEV_Rev1
MODEL := HD
MODEL_SUFFIX := _CC
OPENOCD_JTAG_CONFIG := foss-jtag.revb.cfg
OPENOCD_CONFIG := stm32f1x.cfg
OPENOCD_CONFIG := stm32f3x.cfg
# Note: These must match the values in link_$(BOARD)_memory.ld
BL_BANK_BASE := 0x08000000 # Start of bootloader flash
BL_BANK_SIZE := 0x00004000 # Should include BD_INFO region

View File

@ -25,7 +25,7 @@ endif
include ../board-info.mk
include $(FLIGHT_ROOT_DIR)/make/firmware-defs.mk
# REVO C++ support
# C++ support
USE_CXX = YES
# ARM DSP library
@ -58,6 +58,7 @@ OPTMODULES += Battery
OPTMODULES += ComUsbBridge
OPTMODULES += UAVOMSPBridge
OPTMODULES += UAVOMavlinkBridge
OPTMODULES += UAVOFrSKYSensorHubBridge
SRC += $(FLIGHTLIB)/notification.c
@ -86,11 +87,6 @@ ifndef TESTAPP
SRC += $(PIOSCOMMON)/pios_flashfs_logfs.c
SRC += $(PIOSCOMMON)/pios_flash_jedec.c
#ifeq ($(DEBUG), YES)
SRC += $(OPSYSTEM)/dcc_stdio.c
SRC += $(OPSYSTEM)/cm3_fault_handlers.c
#endif
## Misc library functions
SRC += $(FLIGHTLIB)/instrumentation.c
SRC += $(FLIGHTLIB)/paths.c

View File

@ -1,93 +0,0 @@
/*
* cm3_fault_handlers.c
*
* Created on: Apr 24, 2011
* Author: msmith
*/
#include <stdint.h>
#include "inc/dcc_stdio.h"
#ifdef STM32F4XX
# include <stm32f4xx.h>
#endif
#ifdef STM32F3
# include <stm32f30x.h>
#endif
#ifdef STM32F2XX
# include <stm32f2xx.h>
#endif
#define FAULT_TRAMPOLINE(_vec) \
__attribute__((naked, no_instrument_function)) \
void \
_vec##_Handler(void) \
{ \
__asm(".syntax unified\n" \
"MOVS R0, #4 \n" \
"MOV R1, LR \n" \
"TST R0, R1 \n" \
"BEQ 1f \n" \
"MRS R0, PSP \n" \
"B " #_vec "_Handler2 \n" \
"1: \n" \
"MRS R0, MSP \n" \
"B " #_vec "_Handler2 \n" \
".syntax divided\n"); \
} \
struct hack
struct cm3_frame {
uint32_t r0;
uint32_t r1;
uint32_t r2;
uint32_t r3;
uint32_t r12;
uint32_t lr;
uint32_t pc;
uint32_t psr;
};
FAULT_TRAMPOLINE(HardFault);
FAULT_TRAMPOLINE(BusFault);
FAULT_TRAMPOLINE(UsageFault);
/* this is a hackaround to avoid an issue where dereferencing SCB seems to result in bad codegen and a link error */
#define SCB_REG(_reg) (*(uint32_t *)&(SCB->_reg))
void HardFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nHARD FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(HFSR));
dbg_write_char('\n');
for (;;) {
;
}
}
void BusFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nBUS FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(CFSR));
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(BFAR));
dbg_write_char('\n');
for (;;) {
;
}
}
void UsageFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nUSAGE FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(CFSR));
dbg_write_char('\n');
for (;;) {
;
}
}

View File

@ -1,149 +0,0 @@
/***************************************************************************
* Copyright (C) 2008 by Dominic Rath *
* Dominic.Rath@gmx.de *
* Copyright (C) 2008 by Spencer Oliver *
* spen@spen-soft.co.uk *
* Copyright (C) 2008 by Frederik Kriewtz *
* frederik@kriewitz.eu *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License, or *
* (at your option) any later version. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#include "inc/dcc_stdio.h"
#define TARGET_REQ_TRACEMSG 0x00
#define TARGET_REQ_DEBUGMSG_ASCII 0x01
#define TARGET_REQ_DEBUGMSG_HEXMSG(size) (0x01 | ((size & 0xff) << 8))
#define TARGET_REQ_DEBUGCHAR 0x02
/* we use the cortex_m3 DCRDR reg to simulate a arm7_9 dcc channel
* DCRDR[7:0] is used by target for status
* DCRDR[15:8] is used by target for write buffer
* DCRDR[23:16] is used for by host for status
* DCRDR[31:24] is used for by host for write buffer */
#define NVIC_DBG_DATA_R (*((volatile unsigned short *)0xE000EDF8))
#define BUSY 1
void dbg_write(unsigned long dcc_data)
{
int len = 4;
while (len--) {
/* wait for data ready */
while (NVIC_DBG_DATA_R & BUSY) {
;
}
/* write our data and set write flag - tell host there is data*/
NVIC_DBG_DATA_R = (unsigned short)(((dcc_data & 0xff) << 8) | BUSY);
dcc_data >>= 8;
}
}
void dbg_trace_point(unsigned long number)
{
dbg_write(TARGET_REQ_TRACEMSG | (number << 8));
}
void dbg_write_u32(const unsigned long *val, long len)
{
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(4) | ((len & 0xffff) << 16));
while (len > 0) {
dbg_write(*val);
val++;
len--;
}
}
void dbg_write_u16(const unsigned short *val, long len)
{
unsigned long dcc_data;
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(2) | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = val[0]
| ((len > 1) ? val[1] << 16 : 0x0000);
dbg_write(dcc_data);
val += 2;
len -= 2;
}
}
void dbg_write_u8(const unsigned char *val, long len)
{
unsigned long dcc_data;
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(1) | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = val[0]
| ((len > 1) ? val[1] << 8 : 0x00)
| ((len > 2) ? val[2] << 16 : 0x00)
| ((len > 3) ? val[3] << 24 : 0x00);
dbg_write(dcc_data);
val += 4;
len -= 4;
}
}
void dbg_write_str(const char *msg)
{
long len;
unsigned long dcc_data;
for (len = 0; msg[len] && (len < 65536); len++) {
;
}
dbg_write(TARGET_REQ_DEBUGMSG_ASCII | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = msg[0]
| ((len > 1) ? msg[1] << 8 : 0x00)
| ((len > 2) ? msg[2] << 16 : 0x00)
| ((len > 3) ? msg[3] << 24 : 0x00);
dbg_write(dcc_data);
msg += 4;
len -= 4;
}
}
void dbg_write_char(char msg)
{
dbg_write(TARGET_REQ_DEBUGCHAR | ((msg & 0xff) << 16));
}
void dbg_write_hex32(const unsigned long val)
{
static const char hextab[] = {
'0', '1', '2', '3', '4', '5', '6', '7',
'8', '9', 'a', 'b', 'c', 'd', 'e', 'f'
};
for (int shift = 28; shift >= 0; shift -= 4) {
dbg_write_char(hextab[(val >> shift) & 0xf]);
}
}

View File

@ -1,36 +0,0 @@
/***************************************************************************
* Copyright (C) 2008 by Dominic Rath *
* Dominic.Rath@gmx.de *
* Copyright (C) 2008 by Spencer Oliver *
* spen@spen-soft.co.uk *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License, or *
* (at your option) any later version. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#ifndef DCC_STDIO_H
#define DCC_STDIO_H
void dbg_trace_point(unsigned long number);
void dbg_write_u32(const unsigned long *val, long len);
void dbg_write_u16(const unsigned short *val, long len);
void dbg_write_u8(const unsigned char *val, long len);
void dbg_write_str(const char *msg);
void dbg_write_char(char msg);
void dbg_write_hex32(const unsigned long val);
#endif /* DCC_STDIO_H */

View File

@ -5,8 +5,8 @@
* @addtogroup OpenPilotCore OpenPilot Core
* @{
* @file pios_config.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2013.
* @author LibrePilot, https://bitbucket.org/librepilot, Copyright (C) 2015
* @author LibrePilot, https://bitbucket.org/librepilot, Copyright (C) 2017.
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2013.
* @brief PiOS configuration header, the compile time config file for the PIOS.
* Defines which PiOS libraries and features are included in the firmware.
* @see The GNU Public License (GPL) Version 3

View File

@ -2,7 +2,7 @@
******************************************************************************
*
* @file pios_board.h
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2017.
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
*
* @brief Defines board hardware for the SPRacing F3 EVO board.

View File

@ -7,7 +7,8 @@
* @{
*
* @file pios_usb_board_data.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2017.
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Board specific USB definitions
* @see The GNU Public License (GPL) Version 3
*

View File

@ -6,9 +6,8 @@ HW_TYPE := 0x01
CHIP := STM32F303xC
OPENOCD_JTAG_CONFIG := foss-jtag.revb.cfg
OPENOCD_CONFIG := stm32f1x.cfg
OPENOCD_CONFIG := stm32f3x.cfg
# Note: These must match the values in link_$(BOARD)_memory.ld
BL_BANK_BASE := 0x08000000 # Start of bootloader flash
BL_BANK_SIZE := 0x00004000 # Should include BD_INFO region

View File

@ -87,11 +87,6 @@ ifndef TESTAPP
SRC += $(PIOSCOMMON)/pios_flashfs_logfs.c
SRC += $(PIOSCOMMON)/pios_flash_jedec.c
#ifeq ($(DEBUG), YES)
SRC += $(OPSYSTEM)/dcc_stdio.c
SRC += $(OPSYSTEM)/cm3_fault_handlers.c
#endif
## Misc library functions
SRC += $(FLIGHTLIB)/instrumentation.c
SRC += $(FLIGHTLIB)/paths.c

View File

@ -1,93 +0,0 @@
/*
* cm3_fault_handlers.c
*
* Created on: Apr 24, 2011
* Author: msmith
*/
#include <stdint.h>
#include "inc/dcc_stdio.h"
#ifdef STM32F4XX
# include <stm32f4xx.h>
#endif
#ifdef STM32F3
# include <stm32f30x.h>
#endif
#ifdef STM32F2XX
# include <stm32f2xx.h>
#endif
#define FAULT_TRAMPOLINE(_vec) \
__attribute__((naked, no_instrument_function)) \
void \
_vec##_Handler(void) \
{ \
__asm(".syntax unified\n" \
"MOVS R0, #4 \n" \
"MOV R1, LR \n" \
"TST R0, R1 \n" \
"BEQ 1f \n" \
"MRS R0, PSP \n" \
"B " #_vec "_Handler2 \n" \
"1: \n" \
"MRS R0, MSP \n" \
"B " #_vec "_Handler2 \n" \
".syntax divided\n"); \
} \
struct hack
struct cm3_frame {
uint32_t r0;
uint32_t r1;
uint32_t r2;
uint32_t r3;
uint32_t r12;
uint32_t lr;
uint32_t pc;
uint32_t psr;
};
FAULT_TRAMPOLINE(HardFault);
FAULT_TRAMPOLINE(BusFault);
FAULT_TRAMPOLINE(UsageFault);
/* this is a hackaround to avoid an issue where dereferencing SCB seems to result in bad codegen and a link error */
#define SCB_REG(_reg) (*(uint32_t *)&(SCB->_reg))
void HardFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nHARD FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(HFSR));
dbg_write_char('\n');
for (;;) {
;
}
}
void BusFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nBUS FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(CFSR));
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(BFAR));
dbg_write_char('\n');
for (;;) {
;
}
}
void UsageFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nUSAGE FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(CFSR));
dbg_write_char('\n');
for (;;) {
;
}
}

View File

@ -1,149 +0,0 @@
/***************************************************************************
* Copyright (C) 2008 by Dominic Rath *
* Dominic.Rath@gmx.de *
* Copyright (C) 2008 by Spencer Oliver *
* spen@spen-soft.co.uk *
* Copyright (C) 2008 by Frederik Kriewtz *
* frederik@kriewitz.eu *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License, or *
* (at your option) any later version. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#include "inc/dcc_stdio.h"
#define TARGET_REQ_TRACEMSG 0x00
#define TARGET_REQ_DEBUGMSG_ASCII 0x01
#define TARGET_REQ_DEBUGMSG_HEXMSG(size) (0x01 | ((size & 0xff) << 8))
#define TARGET_REQ_DEBUGCHAR 0x02
/* we use the cortex_m3 DCRDR reg to simulate a arm7_9 dcc channel
* DCRDR[7:0] is used by target for status
* DCRDR[15:8] is used by target for write buffer
* DCRDR[23:16] is used for by host for status
* DCRDR[31:24] is used for by host for write buffer */
#define NVIC_DBG_DATA_R (*((volatile unsigned short *)0xE000EDF8))
#define BUSY 1
void dbg_write(unsigned long dcc_data)
{
int len = 4;
while (len--) {
/* wait for data ready */
while (NVIC_DBG_DATA_R & BUSY) {
;
}
/* write our data and set write flag - tell host there is data*/
NVIC_DBG_DATA_R = (unsigned short)(((dcc_data & 0xff) << 8) | BUSY);
dcc_data >>= 8;
}
}
void dbg_trace_point(unsigned long number)
{
dbg_write(TARGET_REQ_TRACEMSG | (number << 8));
}
void dbg_write_u32(const unsigned long *val, long len)
{
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(4) | ((len & 0xffff) << 16));
while (len > 0) {
dbg_write(*val);
val++;
len--;
}
}
void dbg_write_u16(const unsigned short *val, long len)
{
unsigned long dcc_data;
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(2) | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = val[0]
| ((len > 1) ? val[1] << 16 : 0x0000);
dbg_write(dcc_data);
val += 2;
len -= 2;
}
}
void dbg_write_u8(const unsigned char *val, long len)
{
unsigned long dcc_data;
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(1) | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = val[0]
| ((len > 1) ? val[1] << 8 : 0x00)
| ((len > 2) ? val[2] << 16 : 0x00)
| ((len > 3) ? val[3] << 24 : 0x00);
dbg_write(dcc_data);
val += 4;
len -= 4;
}
}
void dbg_write_str(const char *msg)
{
long len;
unsigned long dcc_data;
for (len = 0; msg[len] && (len < 65536); len++) {
;
}
dbg_write(TARGET_REQ_DEBUGMSG_ASCII | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = msg[0]
| ((len > 1) ? msg[1] << 8 : 0x00)
| ((len > 2) ? msg[2] << 16 : 0x00)
| ((len > 3) ? msg[3] << 24 : 0x00);
dbg_write(dcc_data);
msg += 4;
len -= 4;
}
}
void dbg_write_char(char msg)
{
dbg_write(TARGET_REQ_DEBUGCHAR | ((msg & 0xff) << 16));
}
void dbg_write_hex32(const unsigned long val)
{
static const char hextab[] = {
'0', '1', '2', '3', '4', '5', '6', '7',
'8', '9', 'a', 'b', 'c', 'd', 'e', 'f'
};
for (int shift = 28; shift >= 0; shift -= 4) {
dbg_write_char(hextab[(val >> shift) & 0xf]);
}
}

View File

@ -1,36 +0,0 @@
/***************************************************************************
* Copyright (C) 2008 by Dominic Rath *
* Dominic.Rath@gmx.de *
* Copyright (C) 2008 by Spencer Oliver *
* spen@spen-soft.co.uk *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License, or *
* (at your option) any later version. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#ifndef DCC_STDIO_H
#define DCC_STDIO_H
void dbg_trace_point(unsigned long number);
void dbg_write_u32(const unsigned long *val, long len);
void dbg_write_u16(const unsigned short *val, long len);
void dbg_write_u8(const unsigned char *val, long len);
void dbg_write_str(const char *msg);
void dbg_write_char(char msg);
void dbg_write_hex32(const unsigned long val);
#endif /* DCC_STDIO_H */

View File

@ -56,16 +56,12 @@ else ifneq (,$(findstring STM32F4,$(CHIP)))
# Using the _compat ld script ensure that the bootloader updated is compiled with irqstack in sram
# This allow to be used with bootloader earlier than rel5
LDFLAGS += $(addprefix -T,$(LINKER_SCRIPTS_APP))
SRC += $(HWDEFSINC)/firmware/cm3_fault_handlers.c
SRC += $(HWDEFSINC)/firmware/dcc_stdio.c
else ifneq (,$(findstring STM32F30,$(CHIP)))
include $(PIOS)/stm32f30x/library.mk
# Set linker-script name depending on selected submodel name
# Using the _compat ld script ensure that the bootloader updated is compiled with irqstack in sram
# This allow to be used with bootloader earlier than rel5
# LDFLAGS += $(addprefix -T,$(LINKER_SCRIPTS_APP))
SRC += $(HWDEFSINC)/firmware/cm3_fault_handlers.c
SRC += $(HWDEFSINC)/firmware/dcc_stdio.c
else
$(error Unsupported MCU for BootloaderUpdater: $(CHIP))
endif

View File

@ -265,6 +265,7 @@ void ControllerPage::connectionStatusChanged()
boardPic.load(":/configgadget/images/tinyfish_top.png");
ui->boardImg->setPixmap(boardPic.scaled(picSize, Qt::KeepAspectRatio));
break;
default:
ui->boardImg->setPixmap(QPixmap());
break;