1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-01-30 15:52:12 +01:00

OP-1476 - Fixes for Bootloader

- Allocate 10KBytes for bootloader;
- Replace pios_com_msg with pios_com for ssp support
- Change Speed to 9600 for higher reliability
This commit is contained in:
Alessio Morale 2014-09-07 23:00:00 +02:00
parent 9a55b4ac63
commit 7e73c59e90
13 changed files with 135 additions and 177 deletions

View File

@ -18,6 +18,8 @@
#define FALSE 0
#endif
#define SPP_USES_CRC
#define SSP_TX_IDLE 0 // not expecting a ACK packet (no current transmissions in progress)
#define SSP_TX_WAITING 1 // waiting for a valid ACK to arrive
#define SSP_TX_TIMEOUT 2 // failed to receive a valid ACK in the timeout period, after retrying.

View File

@ -31,7 +31,6 @@
#include <stdbool.h>
#include "op_dfu.h"
#include "pios_bl_helper.h"
#include "pios_com_msg.h"
#include <pios_board_info.h>
// programmable devices
Device devicesTable[10];
@ -71,6 +70,7 @@ DFUTransfer downType = 0;
/* Extern variables ----------------------------------------------------------*/
extern DFUStates DeviceState;
extern uint8_t JumpToApp;
extern int32_t platform_senddata(const uint8_t *msg, uint16_t msg_len);
/* Private function prototypes -----------------------------------------------*/
static uint32_t baseOfAdressType(uint8_t type);
static uint8_t isBiggerThanAvailable(uint8_t type, uint32_t size);
@ -135,12 +135,7 @@ static void pack_uint32(uint32_t value, uint8_t *buffer)
void processComand(uint8_t *xReceive_Buffer)
{
Command = xReceive_Buffer[COMMAND];
#ifdef DEBUG_SSP
char str[63] = { 0 };
sprintf(str, "Received COMMAND:%d|", Command);
PIOS_COM_SendString(PIOS_COM_TELEM_USB, str);
#endif
Command = xReceive_Buffer[COMMAND];
EchoReqFlag = (Command >> 7);
EchoAnsFlag = (Command >> 6) & 0x01;
StartFlag = (Command >> 5) & 0x01;
@ -343,14 +338,7 @@ void processComand(uint8_t *xReceive_Buffer)
}
break;
case Download_Req:
#ifdef DEBUG_SSP
sprintf(str, "COMMAND:DOWNLOAD_REQ 1 Status=%d|", DeviceState);
PIOS_COM_SendString(PIOS_COM_TELEM_USB, str);
#endif
if (DeviceState == DFUidle) {
#ifdef DEBUG_SSP
PIOS_COM_SendString(PIOS_COM_TELEM_USB, "COMMAND:DOWNLOAD_REQ 1|");
#endif
downType = Data0;
downPacketTotal = Count;
downSizeOfLastPacket = Data1;
@ -468,7 +456,7 @@ uint32_t CalcFirmCRC()
}
void sendData(uint8_t *buf, uint16_t size)
{
PIOS_COM_MSG_Send(PIOS_COM_TELEM_USB, buf, size);
platform_senddata(buf, size);
}
bool flash_read(uint8_t *buffer, uint32_t adr, DFUProgType type)

View File

@ -305,7 +305,6 @@ uint16_t ssp_SendDataBlock(Port_t *thisport, uint8_t *data, uint16_t length)
packet_status = ssp_SendProcess(thisport); // check the send status
}
return packet_status == SSP_TX_ACKED; // figure out what happened to the packet
}
/*!

View File

@ -2,12 +2,12 @@
******************************************************************************
* @file system_stm32f0xx.c
* @author MCD Application Team
* @version V1.3.1
* @date 17-January-2014
* @version V1.0.1
* @date 07-September-2014
* @brief CMSIS Cortex-M0 Device Peripheral Access Layer System Source File.
* This file contains the system clock configuration for STM32F0xx devices,
* and is generated by the clock configuration tool
* STM32F0xx_Clock_Configuration_V1.0.0.xls
* STM32f0xx_Clock_Configuration_V1.0.1.xls
*
* 1. This file provides two functions and one global variable to be called from
* user application:
@ -41,33 +41,31 @@
*
* 5. This file configures the system clock as follows:
*=============================================================================
* System Clock Configuration
*=============================================================================
* System Clock source | PLL(HSE)
* System Clock source | PLL (HSE)
*-----------------------------------------------------------------------------
* SYSCLK | 48000000 Hz
* SYSCLK(Hz) | 48000000
*-----------------------------------------------------------------------------
* HCLK | 48000000 Hz
* HCLK(Hz) | 48000000
*-----------------------------------------------------------------------------
* AHB Prescaler | 1
* AHB Prescaler | 1
*-----------------------------------------------------------------------------
* APB1 Prescaler | 1
* APB Prescaler | 1
*-----------------------------------------------------------------------------
* APB2 Prescaler | 1
* HSE Frequency(Hz) | 8000000
*----------------------------------------------------------------------------
* PLLMUL | 6
*-----------------------------------------------------------------------------
* HSE Frequency | 8000000 Hz
* PREDIV | 1
*-----------------------------------------------------------------------------
* PLL MUL | 6
* Flash Latency(WS) | 1
*-----------------------------------------------------------------------------
* VDD | 3.3 V
* Prefetch Buffer | ON
*-----------------------------------------------------------------------------
* Flash Latency | 1 WS
*-----------------------------------------------------------------------------
*=============================================================================
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2014 STMicroelectronics</center></h2>
* <h2><center>&copy; COPYRIGHT 2012 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
@ -113,10 +111,6 @@
/** @addtogroup STM32F0xx_System_Private_Defines
* @{
*/
#define PLL_SOURCE_HSI // HSI (~8MHz) used to clock the PLL, and the PLL is used as system clock source
//#define PLL_SOURCE_HSE // HSE (8MHz) used to clock the PLL, and the PLL is used as system clock source
/**
* @}
*/
@ -133,7 +127,7 @@
* @{
*/
uint32_t SystemCoreClock = 48000000;
const uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
/**
* @}
@ -165,13 +159,8 @@ void SystemInit (void)
/* Set HSION bit */
RCC->CR |= (uint32_t)0x00000001;
#if defined (STM32F031) || defined (STM32F072) || defined (STM32F042)
/* Reset SW[1:0], HPRE[3:0], PPRE[2:0], ADCPRE and MCOSEL[2:0] bits */
RCC->CFGR &= (uint32_t)0xF8FFB80C;
#else
/* Reset SW[1:0], HPRE[3:0], PPRE[2:0], ADCPRE, MCOSEL[2:0], MCOPRE[2:0] and PLLNODIV bits */
RCC->CFGR &= (uint32_t)0x08FFB80C;
#endif /* STM32F031*/
/* Reset HSEON, CSSON and PLLON bits */
RCC->CR &= (uint32_t)0xFEF6FFFF;
@ -287,49 +276,16 @@ void SystemCoreClockUpdate (void)
*/
static void SetSysClock(void)
{
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
/******************************************************************************/
/* PLL (clocked by HSE) used as System clock source */
/******************************************************************************/
/* SYSCLK, HCLK, PCLK configuration ----------------------------------------*/
#if defined (PLL_SOURCE_HSI)
/* At this stage the HSI is already enabled */
/* Enable Prefetch Buffer and set Flash Latency */
FLASH->ACR = FLASH_ACR_PRFTBE | FLASH_ACR_LATENCY;
/* HCLK = SYSCLK */
RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
/* PCLK = HCLK */
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE_DIV1;
/* PLL configuration = (HSI/2) * 12 = ~48 MHz */
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL));
RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSI_Div2 | RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLMULL12);
/* Enable PLL */
RCC->CR |= RCC_CR_PLLON;
/* Wait till PLL is ready */
while((RCC->CR & RCC_CR_PLLRDY) == 0)
{
}
/* Select PLL as system clock source */
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL;
/* Wait till PLL is used as system clock source */
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)RCC_CFGR_SWS_PLL)
{
}
#else
#if defined (PLL_SOURCE_HSE)
/* Enable HSE */
RCC->CR |= ((uint32_t)RCC_CR_HSEON);
#elif defined (PLL_SOURCE_HSE_BYPASS)
/* HSE oscillator bypassed with external clock */
RCC->CR |= (uint32_t)(RCC_CR_HSEON | RCC_CR_HSEBYP);
#endif /* PLL_SOURCE_HSE */
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
/* Wait till HSE is ready and if Time out is reached exit */
do
{
@ -350,17 +306,17 @@ static void SetSysClock(void)
{
/* Enable Prefetch Buffer and set Flash Latency */
FLASH->ACR = FLASH_ACR_PRFTBE | FLASH_ACR_LATENCY;
/* HCLK = SYSCLK */
RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
/* PCLK = HCLK */
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE_DIV1;
/* PLL configuration = HSE * 6 = 48 MHz */
/* HCLK = SYSCLK / 1 */
RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
/* PCLK = HCLK / 1 */
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE_DIV1;
/* PLL configuration */
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL));
RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_PREDIV1 | RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLMULL6);
/* Enable PLL */
RCC->CR |= RCC_CR_PLLON;
@ -381,8 +337,7 @@ static void SetSysClock(void)
else
{ /* If HSE fails to start-up, the application will have wrong clock
configuration. User can add here some code to deal with this error */
}
#endif /* PLL_SOURCE_HSI */
}
}
/**
@ -398,3 +353,4 @@ static void SetSysClock(void)
*/
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

View File

@ -1,8 +1,8 @@
MEMORY
{
BL_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 8K - 0x80
BD_INFO (r) : ORIGIN = 0x08000000 + 8K - 0x80, LENGTH = 0x80
FLASH (rx) : ORIGIN = 0x08000000 + 8K, LENGTH = 32K - 8K
BL_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 10K - 0x80
BD_INFO (r) : ORIGIN = 0x08000000 + 10K - 0x80, LENGTH = 0x80
FLASH (rx) : ORIGIN = 0x08000000 + 10K, LENGTH = 32K - 10K
VTRAM (xrw) : ORIGIN = 0x20000000, LENGTH = 0xc0 /* First part of RAM is reserved to the vector table */
SRAM (rwx) : ORIGIN = 0x20000000 + 0xc0, LENGTH = 4K - 0xc0
}

View File

@ -87,12 +87,7 @@ static bool erase_flash(uint32_t startAddress, uint32_t endAddress)
fail = true;
}
}
#ifdef STM32F10X_HD
pageAddress += 2048;
#elif defined(STM32F10X_MD)
pageAddress += 1024;
#endif
}
return !fail;
}

View File

@ -81,28 +81,10 @@ int32_t PIOS_DELAY_Init(void)
*/
int32_t PIOS_DELAY_WaituS(uint32_t uS)
{
uint32_t elapsed = 0;
uint32_t last_count = DELAY_COUNTER;
for (;;) {
uint32_t current_count = DELAY_COUNTER;
uint32_t elapsed_uS;
/* measure the time elapsed since the last time we checked */
elapsed += current_count - last_count;
last_count = current_count;
/* convert to microseconds */
elapsed_uS = elapsed;
if (elapsed_uS >= uS) {
break;
}
/* reduce the delay by the elapsed time */
uS -= elapsed_uS;
/* keep fractional microseconds for the next iteration */
elapsed = 0;
while (DELAY_COUNTER - last_count <= uS) {
;
}
/* No error */
@ -146,7 +128,7 @@ uint32_t PIOS_DELAY_GetuS(void)
*/
uint32_t PIOS_DELAY_GetuSSince(uint32_t t)
{
return PIOS_DELAY_GetuS() - t;
return DELAY_COUNTER - t;
}
/**

View File

@ -236,6 +236,7 @@ static void PIOS_USART_ChangeBaud(uint32_t usart_id, uint32_t baud)
static void PIOS_USART_RegisterRxCallback(uint32_t usart_id, pios_com_callback rx_in_cb, uint32_t context)
{
struct pios_usart_dev *usart_dev = PIOS_USART_validate(usart_id);
/*
* Order is important in these assignments since ISR uses _cb
* field to determine if it's ok to dereference _cb and _context
@ -264,9 +265,9 @@ static void PIOS_USART_generic_irq_handler(uint32_t usart_id)
/* Check if RXNE flag is set */
bool rx_need_yield = false;
if(USART_GetITStatus(usart_dev->cfg->regs, USART_IT_RXNE) != RESET) {
bool rx_need_yield = false;
if (USART_GetITStatus(usart_dev->cfg->regs, USART_IT_RXNE) != RESET) {
uint8_t byte = USART_ReceiveData(usart_dev->cfg->regs) & 0x00FF;
if (usart_dev->rx_in_cb) {
uint16_t rc;

View File

@ -1,4 +1,4 @@
BOARD_TYPE := 0x09
BOARD_TYPE := 0x0A
BOARD_REVISION := 0x01
BOOTLOADER_VERSION := 0x01
HW_TYPE := 0x01
@ -14,9 +14,9 @@ OPENOCD_CONFIG := stm32f0x.cfg
# Note: These must match the values in link_$(BOARD)_memory.ld
BL_BANK_BASE := 0x08000000 # Start of bootloader flash
BL_BANK_SIZE := 0x00002000 # Should include BD_INFO region
FW_BANK_BASE := 0x08002000 # Start of firmware flash
FW_BANK_SIZE := 0x00006000 # Should include FW_DESC_SIZE
BL_BANK_SIZE := 0x00002800 # Should include BD_INFO region
FW_BANK_BASE := 0x08002800 # Start of firmware flash
FW_BANK_SIZE := 0x00005800 # Should include FW_DESC_SIZE
FW_DESC_SIZE := 0x00000064

View File

@ -267,7 +267,7 @@ static const struct pios_usart_cfg pios_usart_generic_main_cfg = {
.regs = USART1,
.remap = GPIO_AF_1,
.init = {
.USART_BaudRate = 57600,
.USART_BaudRate = 9600,
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1,

View File

@ -29,6 +29,7 @@ include $(ROOT_DIR)/make/firmware-defs.mk
## The standard CMSIS startup
SRC += $(CMSIS_DEVICEDIR)/system_stm32f0xx.c
SRC += $(FLIGHTLIB)/ssp.c
SRC += $(PIOSCOMMON)/pios_com.c
SRC += $(FLIGHTLIB)/fifo_buffer.c

View File

@ -33,22 +33,22 @@
#include <op_dfu.h>
#include <pios_iap.h>
#include <fifo_buffer.h>
#include <pios_com_msg.h>
#include <pios_com.h>
#include <ssp.h>
#include <pios_delay.h>
/* Prototype of PIOS_Board_Init() function */
extern void PIOS_Board_Init(void);
extern void FLASH_Download();
int32_t platform_senddata(const uint8_t *msg, uint16_t msg_len);
/* Private typedef -----------------------------------------------------------*/
typedef void (*pFunction)(void);
/* Private define ------------------------------------------------------------*/
#define MAX_PACKET_DATA_LEN 255
#define MAX_PACKET_BUF_SIZE (1 + 1 + MAX_PACKET_DATA_LEN + 2)
#define UART_BUFFER_SIZE 512
#define UART_BUFFER_SIZE 256
#define BL_WAIT_TIME 6 * 1000 * 1000
#define DFU_BUFFER_SIZE 63
#define DFU_BUFFER_SIZE 63
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
@ -56,21 +56,21 @@ pFunction Jump_To_Application;
static uint32_t JumpAddress;
/// LEDs PWM
static uint16_t period1; // 5 mS
static uint16_t sweep_steps1; // * 5 mS -> 500 mS
//static uint16_t period2 = 5000; // 5 mS
//static uint16_t sweep_steps2 = 100; // * 5 mS -> 500 mS
uint32_t period1 = 5000; // 5 mS
uint32_t sweep_steps1 = 100; // * 5 mS -> 500 mS
uint32_t period2 = 5000; // 5 mS
uint32_t sweep_steps2 = 100; // * 5 mS -> 500 mS
static uint8_t mReceive_Buffer[DFU_BUFFER_SIZE];
static uint8_t process_buffer[DFU_BUFFER_SIZE];
static uint8_t rx_buffer[UART_BUFFER_SIZE];
static uint8_t ssp_txBuf[MAX_PACKET_BUF_SIZE];
static uint8_t ssp_rxBuf[MAX_PACKET_BUF_SIZE];
static uint8_t txBuf[MAX_PACKET_BUF_SIZE];
static uint8_t rxBuf[MAX_PACKET_BUF_SIZE];
/* Extern variables ----------------------------------------------------------*/
DFUStates DeviceState = DFUidle;
int16_t status = 0;
bool JumpToApp = false;
bool GO_dfu = false;
bool ssp_dfu = false; // signal that ssp data has been received
bool User_DFU_request = true;
@ -84,19 +84,19 @@ static void jump_to_app();
static void SSP_CallBack(uint8_t *buf, uint16_t len);
static int16_t SSP_SerialRead(void);
static void SSP_SerialWrite(uint8_t);
static uint32_t SSP_GetTime(void);
static const PortConfig_t ssp_portConfig = {
.rxBuf = ssp_rxBuf,
.rxBuf = rxBuf,
.rxBufSize = MAX_PACKET_DATA_LEN,
.txBuf = ssp_txBuf,
.txBuf = txBuf,
.txBufSize = MAX_PACKET_DATA_LEN,
.max_retry = 10,
.timeoutLen = 1000,
.max_retry = 1,
.timeoutLen = 5000,
.pfCallBack = SSP_CallBack,
.pfSerialRead = SSP_SerialRead,
.pfSerialWrite = SSP_SerialWrite,
.pfGetTime = SSP_GetTime,
.pfGetTime = PIOS_DELAY_GetuS,
};
static Port_t ssp_port;
@ -109,53 +109,70 @@ int main()
PIOS_IAP_Init();
if (PIOS_IAP_CheckRequest() == false) {
PIOS_DELAY_WaitmS(1000);
PIOS_DELAY_WaitmS(500);
User_DFU_request = false;
DeviceState = BLidle;
PIOS_IAP_ClearRequest();
}
// Initialize the SSP layer between serial port and DFU
fifoBuf_init(&ssp_buffer, rx_buffer, UART_BUFFER_SIZE);
ssp_Init(&ssp_port, &ssp_portConfig);
GO_dfu = User_DFU_request;
JumpToApp = !User_DFU_request;
uint32_t stopwatch = 0;
uint32_t stopwatch = 0;
const uint32_t start_time = PIOS_DELAY_GetuS();
while (true) {
/* Update the stopwatch */
stopwatch = PIOS_DELAY_GetuSSince(start_time);
if (JumpToApp == true) {
jump_to_app();
}
stopwatch = PIOS_DELAY_GetuSSince(start_time);
processRX();
switch (DeviceState) {
case Last_operation_Success:
case uploadingStarting:
case DFUidle:
period1 = 5000;
sweep_steps1 = 100;
//PIOS_LED_Off(PIOS_LED_HEARTBEAT);
period2 = 0;
break;
case uploading:
period1 = 5000;
sweep_steps1 = 100;
period2 = 2500;
sweep_steps2 = 50;
break;
case downloading:
period1 = 2500;
sweep_steps1 = 50;
//PIOS_LED_Off(PIOS_LED_HEARTBEAT);
period2 = 0;
break;
case BLidle:
period1 = 0;
sweep_steps1 = 100;
PIOS_LED_On(PIOS_LED_HEARTBEAT);
period2 = 0;
break;
default:
default: // error
period1 = 5000;
sweep_steps1 = 100;
period2 = 5000;
sweep_steps2 = 100;
}
led_pwm_step(period1, sweep_steps1, stopwatch, true);
// led_pwm_step(period2, sweep_steps2, stopwatch, false);
led_pwm_step(period1, sweep_steps1, stopwatch, false);
led_pwm_step(period2, sweep_steps2, stopwatch, true);
JumpToApp |= (stopwatch > BL_WAIT_TIME) && ((DeviceState == BLidle) || (DeviceState == DFUidle));
DataDownload(start);
if (JumpToApp == true && !ssp_dfu) {
jump_to_app();
}
}
}
void led_pwm_step(uint16_t pwm_period, uint16_t pwm_sweep_steps, uint32_t stopwatch, bool default_state){
void led_pwm_step(uint16_t pwm_period, uint16_t pwm_sweep_steps, uint32_t stopwatch, bool default_state)
{
if (pwm_period != 0) {
if (LedPWM(pwm_period, pwm_sweep_steps, stopwatch)) {
PIOS_LED_On(PIOS_LED_HEARTBEAT);
@ -163,7 +180,7 @@ void led_pwm_step(uint16_t pwm_period, uint16_t pwm_sweep_steps, uint32_t stopwa
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
}
} else {
if(default_state){
if (default_state) {
PIOS_LED_On(PIOS_LED_HEARTBEAT);
} else {
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
@ -195,7 +212,7 @@ void jump_to_app()
uint32_t LedPWM(uint16_t pwm_period, uint16_t pwm_sweep_steps, uint32_t count)
{
const uint32_t curr_step = (count / pwm_period) % pwm_sweep_steps; /* 0 - pwm_sweep_steps */
uint32_t pwm_duty = pwm_period * curr_step / pwm_sweep_steps; /* fraction of pwm_period */
uint32_t pwm_duty = pwm_period * curr_step / pwm_sweep_steps; /* fraction of pwm_period */
const uint32_t curr_sweep = (count / (pwm_period * pwm_sweep_steps)); /* ticks once per full sweep */
@ -204,24 +221,30 @@ uint32_t LedPWM(uint16_t pwm_period, uint16_t pwm_sweep_steps, uint32_t count)
}
return ((count % pwm_period) > pwm_duty) ? 1 : 0;
}
uint32_t process_count = 0;
void processRX()
{
do{
do {
ssp_ReceiveProcess(&ssp_port);
status = ssp_SendProcess(&ssp_port);
}while ((status != SSP_TX_IDLE) && (status != SSP_TX_ACKED));
} while ((status != SSP_TX_IDLE) && (status != SSP_TX_ACKED));
if (fifoBuf_getUsed(&ssp_buffer) >= DFU_BUFFER_SIZE) {
for (int32_t x = 0; x < DFU_BUFFER_SIZE; ++x) {
mReceive_Buffer[x] = fifoBuf_getByte(&ssp_buffer);
process_buffer[x] = fifoBuf_getByte(&ssp_buffer);
}
processComand(mReceive_Buffer);
process_count++;
processComand(process_buffer);
}
}
uint32_t callback_cnt = 0;
uint32_t read_cnt = 0;
uint32_t write_cnt = 0;
uint32_t rx_check_cnt = 0;
void SSP_CallBack(uint8_t *buf, uint16_t len)
{
ssp_dfu = true;
callback_cnt++;
fifoBuf_putData(&ssp_buffer, buf, len);
}
@ -229,20 +252,22 @@ int16_t SSP_SerialRead(void)
{
uint8_t byte;
if (PIOS_COM_MSG_Receive(PIOS_COM_TELEM_USB, &byte, 1) == 1) {
rx_check_cnt++;
if (PIOS_COM_ReceiveBuffer(PIOS_COM_TELEM_USB, &byte, 1, 0) == 1) {
read_cnt++;
return byte;
} else {
return -1;
}
}
int32_t platform_senddata(const uint8_t *msg, uint16_t msg_len)
{
return ssp_SendData(&ssp_port, msg, msg_len);
}
void SSP_SerialWrite(uint8_t value)
{
PIOS_COM_MSG_Send(PIOS_COM_TELEM_USB, &value, 1);
}
uint32_t SSP_GetTime(void)
{
return PIOS_DELAY_GetuS();
write_cnt++;
PIOS_COM_SendChar(PIOS_COM_TELEM_USB, value);
}

View File

@ -37,6 +37,11 @@
#include "../board_hw_defs.c"
#include <pios_com_msg.h>
uint32_t PIOS_COM_TELEM_USB;
#define PIOS_COM_MAIN_RX_BUF_LEN 256
#define PIOS_COM_MAIN_TX_BUF_LEN 256
uint8_t rx_buffer[PIOS_COM_MAIN_RX_BUF_LEN];
uint8_t tx_buffer[PIOS_COM_MAIN_TX_BUF_LEN];
static void setupCom();
/**
@ -48,6 +53,8 @@ void PIOS_Board_Init(void)
{
const struct pios_board_info *bdinfo = &pios_board_info_blob;
FLASH_PrefetchBufferCmd(ENABLE);
#if defined(PIOS_INCLUDE_LED)
const struct pios_gpio_cfg *led_cfg = PIOS_BOARD_HW_DEFS_GetLedCfg(bdinfo->board_rev);
PIOS_Assert(led_cfg);
@ -62,7 +69,9 @@ void setupCom()
if (PIOS_USART_Init(&pios_usart_generic_id, &pios_usart_generic_main_cfg)) {
PIOS_Assert(0);
}
if (PIOS_COM_MSG_Init(&PIOS_COM_TELEM_USB, &pios_usart_com_driver, pios_usart_generic_id)) {
if (PIOS_COM_Init(&PIOS_COM_TELEM_USB, &pios_usart_com_driver, pios_usart_generic_id,
rx_buffer, PIOS_COM_MAIN_RX_BUF_LEN,
tx_buffer, PIOS_COM_MAIN_TX_BUF_LEN)) {
PIOS_Assert(0);
}
}