1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-02-19 09:54:15 +01:00

hwinit: Convert COM and USART to dynamic init

git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2771 ebee16cc-31ac-478f-84a7-5cbb03baadba
This commit is contained in:
stac 2011-02-12 22:19:43 +00:00 committed by stac
parent ec8135bd5d
commit 841b0d3d6d
21 changed files with 807 additions and 922 deletions

View File

@ -118,7 +118,7 @@ struct altitude_sensor altitude_data;
struct gps_sensor gps_data;
//! The oversampling rate, ekf is 2k / this
static uint8_t adc_oversampling = 15;
uint8_t adc_oversampling = 15;
//! Offset correction of barometric alt, to match gps data
static float baro_offset = 0;
@ -128,7 +128,6 @@ volatile int32_t ekf_too_slow;
volatile int32_t total_conversion_blocks;
//! Buffer to allow ADC to run a bit faster than EKF
uint8_t adc_fifo_buf[sizeof(float) * 6 * 4] __attribute__ ((aligned(4))); // align to 32-bit to try and provide speed improvement
t_fifo_buffer adc_fifo_buffer;
@ -529,6 +528,8 @@ void print_ahrs_raw()
}
#endif
extern void PIOS_Board_Init(void);
/**
* @brief AHRS Main function
*/
@ -546,35 +547,9 @@ int main()
uint32_t counter_val = 0;
ahrs_algorithm = AHRSSETTINGS_ALGORITHM_SIMPLE;
/* Brings up System using CMSIS functions, enables the LEDs. */
PIOS_SYS_Init();
PIOS_Board_Init();
PIOS_LED_On(LED1);
/* Delay system */
PIOS_DELAY_Init();
/* Communication system */
PIOS_COM_Init();
/* IAP System Setup */
PIOS_IAP_Init();
/* ADC system */
PIOS_ADC_Init();
PIOS_ADC_Config(adc_oversampling);
PIOS_ADC_SetCallback(adc_callback);
/* ADC buffer */
fifoBuf_init(&adc_fifo_buffer, adc_fifo_buf, sizeof(adc_fifo_buf));
/* Setup the Accelerometer FS (Full-Scale) GPIO */
PIOS_GPIO_Enable(0);
SET_ACCEL_6G;
#if defined(PIOS_INCLUDE_HMC5843) && defined(PIOS_INCLUDE_I2C)
/* Magnetic sensor system */
PIOS_I2C_Init();
PIOS_HMC5843_Init();
// Get 3 ID bytes
strcpy((char *)mag_data.id, "ZZZ");
PIOS_HMC5843_ReadID(mag_data.id);

View File

@ -260,48 +260,18 @@ const struct pios_usart_cfg pios_usart_aux_cfg = {
},
};
/*
* Board specific number of devices.
*/
struct pios_usart_dev pios_usart_devs[] = {
#define PIOS_USART_AUX 0
{
.cfg = &pios_usart_aux_cfg,
},
};
uint8_t pios_usart_num_devices = NELEMENTS(pios_usart_devs);
static uint32_t pios_usart_aux_id;
void PIOS_USART_aux_irq_handler(void)
{
PIOS_USART_IRQ_Handler(PIOS_USART_AUX);
PIOS_USART_IRQ_Handler(pios_usart_aux_id);
}
#endif /* PIOS_INCLUDE_USART */
#if defined(PIOS_INCLUDE_COM)
#include <pios_com_priv.h>
/*
* COM devices
*/
/*
* Board specific number of devices.
*/
extern const struct pios_com_driver pios_usart_com_driver;
struct pios_com_dev pios_com_devs[] = {
#if defined(PIOS_INCLUDE_USART)
{
.id = PIOS_USART_AUX,
.driver = &pios_usart_com_driver,
},
#endif
};
const uint8_t pios_com_num_devices = NELEMENTS(pios_com_devs);
#endif /* PIOS_INCLUDE_COM */
#if defined(PIOS_INCLUDE_I2C)
@ -413,4 +383,61 @@ static const struct stm32_gpio pios_debug_pins[] = {
},
};
#endif /* PIOS_ENABLE_DEBUG_PINS */
#endif /* PIOS_ENABLE_DEBUG_PINS */
extern const struct pios_com_driver pios_usart_com_driver;
uint32_t pios_com_aux_id;
uint8_t adc_fifo_buf[sizeof(float) * 6 * 4] __attribute__ ((aligned(4))); // align to 32-bit to try and provide speed improvement
/**
* PIOS_Board_Init()
* initializes all the core subsystems on this specific hardware
* called from System/openpilot.c
*/
void PIOS_Board_Init(void) {
/* Brings up System using CMSIS functions, enables the LEDs. */
PIOS_SYS_Init();
PIOS_LED_On(LED1);
/* Delay system */
PIOS_DELAY_Init();
/* Communication system */
#if !defined(PIOS_ENABLE_DEBUG_PINS)
#if defined(PIOS_INCLUDE_COM)
if (PIOS_USART_Init(&pios_usart_aux_id, &pios_usart_aux_cfg)) {
PIOS_DEBUG_Assert(0);
}
if (PIOS_COM_Init(&pios_com_aux_id, &pios_usart_com_driver, pios_usart_aux_id)) {
PIOS_DEBUG_Assert(0);
}
#endif /* PIOS_INCLUDE_COM */
#endif
/* IAP System Setup */
PIOS_IAP_Init();
/* ADC system */
PIOS_ADC_Init();
extern uint8_t adc_oversampling;
PIOS_ADC_Config(adc_oversampling);
extern void adc_callback(float *);
PIOS_ADC_SetCallback(adc_callback);
/* ADC buffer */
extern t_fifo_buffer adc_fifo_buffer;
fifoBuf_init(&adc_fifo_buffer, adc_fifo_buf, sizeof(adc_fifo_buf));
/* Setup the Accelerometer FS (Full-Scale) GPIO */
PIOS_GPIO_Enable(0);
SET_ACCEL_6G;
#if defined(PIOS_INCLUDE_HMC5843) && defined(PIOS_INCLUDE_I2C)
/* Magnetic sensor system */
PIOS_I2C_Init();
PIOS_HMC5843_Init();
#endif
}

View File

@ -29,65 +29,10 @@
#include <pios.h>
#include <pios_spi_priv.h>
#include <pios_usart_priv.h>
#include <pios_com_priv.h>
#include <pios_i2c_priv.h>
#include <openpilot.h>
#include <uavobjectsinit.h>
/**
* PIOS_Board_Init()
* initializes all the core subsystems on this specific hardware
* called from System/openpilot.c
*/
void PIOS_Board_Init(void) {
/* Delay system */
PIOS_DELAY_Init();
/* SPI Init */
PIOS_SPI_Init();
PIOS_Flash_W25X_Init();
#if defined(PIOS_INCLUDE_SPEKTRUM)
/* SPEKTRUM init must come before comms */
PIOS_SPEKTRUM_Init();
#endif
/* Initialize UAVObject libraries */
EventDispatcherInitialize();
UAVObjInitialize();
UAVObjectsInitializeAll();
/* Initialize the alarms library */
AlarmsInitialize();
/* Initialize the task monitor library */
TaskMonitorInitialize();
/* Initialize the PiOS library */
PIOS_COM_Init();
/* Remap AFIO pin */
GPIO_PinRemapConfig( GPIO_Remap_SWJ_NoJTRST, ENABLE);
PIOS_Servo_Init();
PIOS_ADC_Init();
PIOS_GPIO_Init();
#if defined(PIOS_INCLUDE_PWM)
PIOS_PWM_Init();
#endif
#if defined(PIOS_INCLUDE_PPM)
PIOS_PPM_Init();
#endif
#if defined(PIOS_INCLUDE_USB_HID)
PIOS_USB_HID_Init(0);
#endif
PIOS_I2C_Init();
PIOS_IAP_Init();
PIOS_WDG_Init();
}
/* Flash/Accel Interface
*
* NOTE: Leave this declared as const data so that it ends up in the
@ -256,6 +201,9 @@ void PIOS_ADC_handler() {
PIOS_ADC_DMA_Handler();
}
#if defined(PIOS_INCLUDE_USART)
#include "pios_usart_priv.h"
/*
* Telemetry USART
@ -303,7 +251,7 @@ const struct pios_usart_cfg pios_usart_telem_cfg = {
},
};
#ifdef PIOS_COM_GPS
#if defined(PIOS_INCLUDE_GPS)
/*
* GPS USART
*/
@ -351,56 +299,64 @@ const struct pios_usart_cfg pios_usart_gps_cfg = {
};
#endif
#ifdef PIOS_COM_SPEKTRUM
#if defined(PIOS_INCLUDE_SPEKTRUM)
/*
* SPEKTRUM USART
*/
#include <pios_spektrum_priv.h>
void PIOS_USART_spektrum_irq_handler(void);
void USART3_IRQHandler() __attribute__ ((alias ("PIOS_USART_spektrum_irq_handler")));
const struct pios_usart_cfg pios_usart_spektrum_cfg = {
.regs = USART3,
.init = {
#if defined (PIOS_COM_SPEKTRUM_BAUDRATE)
.USART_BaudRate = PIOS_COM_SPEKTRUM_BAUDRATE,
#else
.USART_BaudRate = 115200,
#endif
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1,
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
.USART_Mode = USART_Mode_Rx,
},
.irq = {
.handler = PIOS_USART_spektrum_irq_handler,
.init = {
.NVIC_IRQChannel = USART3_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_11,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_IPU,
},
},
.tx = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
},
},
};
static uint32_t pios_usart_spektrum_id;
void PIOS_USART_spektrum_irq_handler(void)
{
SPEKTRUM_IRQHandler(pios_usart_spektrum_id);
}
#include <pios_spektrum_priv.h>
void TIM2_IRQHandler();
void TIM2_IRQHandler() __attribute__ ((alias ("PIOS_TIM2_irq_handler")));
const struct pios_spektrum_cfg pios_spektrum_cfg = {
.pios_usart_spektrum_cfg = {
.regs = USART3,
.init = {
#if defined (PIOS_COM_SPEKTRUM_BAUDRATE)
.USART_BaudRate = PIOS_COM_SPEKTRUM_BAUDRATE,
#else
.USART_BaudRate = 115200,
#endif
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1,
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
.USART_Mode = USART_Mode_Rx,
},
.irq = {
.handler = PIOS_USART_spektrum_irq_handler,
.init = {
.NVIC_IRQChannel = USART3_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_11,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_IPU,
},
},
.tx = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
},
},
},
.pios_usart_spektrum_cfg = pios_usart_spektrum_cfg;
.tim_base_init = {
.TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1, /* For 1 uS accuracy */
.TIM_ClockDivision = TIM_CKD_DIV1,
@ -431,88 +387,29 @@ void PIOS_TIM2_irq_handler()
{
PIOS_SPEKTRUM_irq_handler();
}
#endif
/*
* Board specific number of devices.
*/
struct pios_usart_dev pios_usart_devs[] = {
#define PIOS_USART_TELEM 0
{
.cfg = &pios_usart_telem_cfg,
},
#ifdef PIOS_COM_GPS
#define PIOS_USART_GPS 1
{
.cfg = &pios_usart_gps_cfg,
},
#endif
#ifdef PIOS_COM_SPEKTRUM
#define PIOS_USART_AUX 2
{
.cfg = &pios_spektrum_cfg.pios_usart_spektrum_cfg,
},
#endif
};
uint8_t pios_usart_num_devices = NELEMENTS(pios_usart_devs);
#endif /* PIOS_INCLUDE_SPEKTRUM */
static uint32_t pios_usart_telem_rf_id;
void PIOS_USART_telem_irq_handler(void)
{
PIOS_USART_IRQ_Handler(PIOS_USART_TELEM);
PIOS_USART_IRQ_Handler(pios_usart_telem_rf_id);
}
#ifdef PIOS_COM_GPS
#if defined(PIOS_INCLUDE_GPS)
static uint32_t pios_usart_gps_id;
void PIOS_USART_gps_irq_handler(void)
{
PIOS_USART_IRQ_Handler(PIOS_USART_GPS);
PIOS_USART_IRQ_Handler(pios_usart_gps_id);
}
#endif
#endif /* PIOS_INCLUDE_GPS */
#ifdef PIOS_COM_SPEKTRUM
void PIOS_USART_spektrum_irq_handler(void)
{
SPEKTRUM_IRQHandler();
}
#endif
#endif /* PIOS_INCLUDE_USART */
/*
* COM devices
*/
#if defined(PIOS_INCLUDE_COM)
/*
* Board specific number of devices.
*/
extern const struct pios_com_driver pios_usart_com_driver;
extern const struct pios_com_driver pios_usb_com_driver;
struct pios_com_dev pios_com_devs[] = {
{
.id = PIOS_USART_TELEM,
.driver = &pios_usart_com_driver,
},
#if defined(PIOS_INCLUDE_USB_HID)
{
.id = 0,
.driver = &pios_usb_com_driver,
},
#endif
#ifdef PIOS_COM_GPS
{
.id = PIOS_USART_GPS,
.driver = &pios_usart_com_driver,
},
#endif
#ifdef PIOS_COM_SPEKTRUM
{
.id = PIOS_USART_AUX,
.driver = &pios_usart_com_driver,
},
#endif
};
const uint8_t pios_com_num_devices = NELEMENTS(pios_com_devs);
#include "pios_com_priv.h"
#endif /* PIOS_INCLUDE_COM */
/*
* Servo outputs
@ -768,6 +665,86 @@ void PIOS_I2C_main_adapter_er_irq_handler(void)
PIOS_I2C_ER_IRQ_Handler(PIOS_I2C_MAIN_ADAPTER);
}
extern const struct pios_com_driver pios_usb_com_driver;
uint32_t pios_com_telem_rf_id;
uint32_t pios_com_telem_usb_id;
uint32_t pios_com_gps_id;
uint32_t pios_com_spektrum_id;
/**
* PIOS_Board_Init()
* initializes all the core subsystems on this specific hardware
* called from System/openpilot.c
*/
void PIOS_Board_Init(void) {
/* Delay system */
PIOS_DELAY_Init();
/* SPI Init */
PIOS_SPI_Init();
PIOS_Flash_W25X_Init();
#if defined(PIOS_INCLUDE_SPEKTRUM)
/* SPEKTRUM init must come before comms */
PIOS_SPEKTRUM_Init();
#endif
/* Initialize UAVObject libraries */
EventDispatcherInitialize();
UAVObjInitialize();
UAVObjectsInitializeAll();
/* Initialize the alarms library */
AlarmsInitialize();
/* Initialize the task monitor library */
TaskMonitorInitialize();
/* Initialize the PiOS library */
#if defined(PIOS_INCLUDE_COM)
if (PIOS_USART_Init(&pios_usart_telem_rf_id, &pios_usart_telem_cfg)) {
PIOS_DEBUG_Assert(0);
}
if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_usart_com_driver, pios_usart_telem_rf_id)) {
PIOS_DEBUG_Assert(0);
}
#if defined(PIOS_INCLUDE_GPS)
if (PIOS_USART_Init(&pios_usart_gps_id, &pios_usart_gps_cfg)) {
PIOS_DEBUG_Assert(0);
}
if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_gps_id)) {
PIOS_DEBUG_Assert(0);
}
#endif /* PIOS_INCLUDE_GPS */
#endif /* PIOS_INCLUDE_COM */
/* Remap AFIO pin */
GPIO_PinRemapConfig( GPIO_Remap_SWJ_NoJTRST, ENABLE);
PIOS_Servo_Init();
PIOS_ADC_Init();
PIOS_GPIO_Init();
#if defined(PIOS_INCLUDE_PWM)
PIOS_PWM_Init();
#endif
#if defined(PIOS_INCLUDE_PPM)
PIOS_PPM_Init();
#endif
#if defined(PIOS_INCLUDE_USB_HID)
PIOS_USB_HID_Init(0);
#if defined(PIOS_INCLUDE_COM)
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_com_driver, 0)) {
PIOS_DEBUG_Assert(0);
}
#endif /* PIOS_INCLUDE_COM */
#endif
PIOS_I2C_Init();
PIOS_IAP_Init();
PIOS_WDG_Init();
}
/**
* @}
*/

View File

@ -58,7 +58,7 @@ static void setHomeLocation(GPSPositionData * gpsData);
// Private types
// Private variables
static uint8_t gpsPort;
static uint32_t gpsPort;
static xTaskHandle gpsTaskHandle;
static char gps_rx_buffer[NMEA_BUFFERSIZE];
@ -182,7 +182,7 @@ static void gpsTask(void *parameters)
}
}
}
// Check for GPS timeout
timeNowMs = xTaskGetTickCount() * portTICK_RATE_MS;
if ((timeNowMs - timeOfLastUpdateMs) > GPS_TIMEOUT_MS) {
@ -194,7 +194,7 @@ static void gpsTask(void *parameters)
// Had an update
HomeLocationData home;
HomeLocationGet(&home);
GPSPositionGet(&GpsData);
if ((GpsData.Status == GPSPOSITION_STATUS_FIX3D) && (home.Set == HOMELOCATION_SET_FALSE)) {
setHomeLocation(&GpsData);
@ -206,7 +206,7 @@ static void gpsTask(void *parameters)
else if (GpsData.Status == GPSPOSITION_STATUS_FIX3D) AlarmsSet(SYSTEMALARMS_ALARM_GPS, SYSTEMALARMS_ALARM_WARNING);
else AlarmsSet(SYSTEMALARMS_ALARM_GPS, SYSTEMALARMS_ALARM_CRITICAL);
}
// Block task until next update
vTaskDelay(xDelay);
}
@ -219,8 +219,7 @@ static void setHomeLocation(GPSPositionData * gpsData)
GPSTimeData gps;
GPSTimeGet(&gps);
if (gps.Year >= 2000)
{
if (gps.Year >= 2000) {
// Store LLA
home.Latitude = gpsData->Latitude;
home.Longitude = gpsData->Longitude;

View File

@ -49,7 +49,7 @@
// Private types
// Private variables
static uint8_t telemetryPort;
static uint32_t telemetryPort;
static xQueueHandle queue;
#if defined(PIOS_TELEM_PRIORITY_QUEUE)
@ -290,7 +290,7 @@ static void telemetryTxPriTask(void *parameters)
*/
static void telemetryRxTask(void *parameters)
{
uint8_t inputPort;
uint32_t inputPort;
int32_t len;
// Task loop
@ -324,7 +324,7 @@ static void telemetryRxTask(void *parameters)
*/
static int32_t transmitData(uint8_t * data, int32_t length)
{
uint8_t outputPort;
uint32_t outputPort;
// Determine input port (USB takes priority over telemetry port)
#if defined(PIOS_INCLUDE_USB_HID)

View File

@ -29,66 +29,10 @@
#include <pios.h>
#include <pios_spi_priv.h>
#include <pios_usart_priv.h>
#include <pios_com_priv.h>
#include <pios_i2c_priv.h>
#include <openpilot.h>
#include <uavobjectsinit.h>
/**
* PIOS_Board_Init()
* initializes all the core subsystems on this specific hardware
* called from System/openpilot.c
*/
void PIOS_Board_Init(void) {
/* Remap AFIO pin */
//GPIO_PinRemapConfig( GPIO_Remap_SWJ_NoJTRST, ENABLE);
/* Delay system */
PIOS_DELAY_Init();
/* SPI Init */
PIOS_SPI_Init();
/* Enable and mount the SDCard */
PIOS_SDCARD_Init();
PIOS_SDCARD_MountFS(0);
#if defined(PIOS_INCLUDE_SPEKTRUM)
/* SPEKTRUM init must come before comms */
PIOS_SPEKTRUM_Init();
#endif
/* Initialize UAVObject libraries */
EventDispatcherInitialize();
UAVObjInitialize();
UAVObjectsInitializeAll();
/* Initialize the alarms library */
AlarmsInitialize();
/* Initialize the task monitor library */
TaskMonitorInitialize();
/* Initialize the PiOS library */
PIOS_COM_Init();
PIOS_Servo_Init();
PIOS_ADC_Init();
PIOS_GPIO_Init();
#if defined(PIOS_INCLUDE_PWM)
PIOS_PWM_Init();
#endif
#if defined(PIOS_INCLUDE_PPM)
PIOS_PPM_Init();
#endif
#if defined(PIOS_INCLUDE_USB_HID)
PIOS_USB_HID_Init(0);
#endif
PIOS_I2C_Init();
PIOS_IAP_Init();
PIOS_WDG_Init();
}
/* MicroSD Interface
*
* NOTE: Leave this declared as const data so that it ends up in the
@ -364,6 +308,9 @@ void PIOS_ADC_handler() {
PIOS_ADC_DMA_Handler();
}
#if defined(PIOS_INCLUDE_USART)
#include "pios_usart_priv.h"
/*
* Telemetry USART
@ -512,52 +459,60 @@ const struct pios_usart_cfg pios_usart_aux_cfg = {
/*
* SPEKTRUM USART
*/
#include <pios_spektrum_priv.h>
void PIOS_USART_spektrum_irq_handler(void);
void USART1_IRQHandler() __attribute__ ((alias ("PIOS_USART_spektrum_irq_handler")));
const struct pios_usart_cfg pios_usart_spektrum_cfg = {
.regs = USART1,
.init = {
#if defined (PIOS_COM_SPEKTRUM_BAUDRATE)
.USART_BaudRate = PIOS_COM_SPEKTRUM_BAUDRATE,
#else
.USART_BaudRate = 115200,
#endif
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1,
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
.USART_Mode = USART_Mode_Rx,
},
.irq = {
.handler = PIOS_USART_spektrum_irq_handler,
.init = {
.NVIC_IRQChannel = USART1_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_IPU,
},
},
.tx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_9,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
},
},
};
static uint32_t pios_usart_spektrum_id;
void PIOS_USART_spektrum_irq_handler(void)
{
SPEKTRUM_IRQHandler(pios_usart_spektrum_id);
}
#include <pios_spektrum_priv.h>
void TIM6_IRQHandler();
void TIM6_IRQHandler() __attribute__ ((alias ("PIOS_TIM6_irq_handler")));
const struct pios_spektrum_cfg pios_spektrum_cfg = {
.pios_usart_spektrum_cfg = {
.regs = USART1,
.init = {
#if defined (PIOS_COM_SPEKTRUM_BAUDRATE)
.USART_BaudRate = PIOS_COM_SPEKTRUM_BAUDRATE,
#else
.USART_BaudRate = 115200,
#endif
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1,
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
.USART_Mode = USART_Mode_Rx,
},
.irq = {
.handler = PIOS_USART_spektrum_irq_handler,
.init = {
.NVIC_IRQChannel = USART1_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_IPU,
},
},
.tx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_9,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
},
},
},
.pios_usart_spektrum_cfg = pios_usart_spektrum_cfg,
.tim_base_init = {
.TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1, /* For 1 uS accuracy */
.TIM_ClockDivision = TIM_CKD_DIV1,
@ -588,59 +543,35 @@ void PIOS_TIM6_irq_handler()
{
PIOS_SPEKTRUM_irq_handler();
}
#endif
/*
* Board specific number of devices.
*/
struct pios_usart_dev pios_usart_devs[] = {
#define PIOS_USART_TELEM 0
{
.cfg = &pios_usart_telem_cfg,
},
#define PIOS_USART_GPS 1
{
.cfg = &pios_usart_gps_cfg,
},
#ifdef PIOS_COM_AUX
#define PIOS_USART_AUX 2
{
.cfg = &pios_usart_aux_cfg,
},
#endif
#ifdef PIOS_COM_SPEKTRUM
#define PIOS_USART_AUX 2
{
.cfg = &pios_spektrum_cfg.pios_usart_spektrum_cfg,
},
#endif
};
uint8_t pios_usart_num_devices = NELEMENTS(pios_usart_devs);
#endif /* PIOS_COM_SPEKTRUM */
static uint32_t pios_usart_telem_rf_id;
void PIOS_USART_telem_irq_handler(void)
{
PIOS_USART_IRQ_Handler(PIOS_USART_TELEM);
PIOS_USART_IRQ_Handler(pios_usart_telem_rf_id);
}
static uint32_t pios_usart_gps_id;
void PIOS_USART_gps_irq_handler(void)
{
PIOS_USART_IRQ_Handler(PIOS_USART_GPS);
PIOS_USART_IRQ_Handler(pios_usart_gps_id);
}
#ifdef PIOS_COM_AUX
static uint32_t pios_usart_aux_id;
void PIOS_USART_aux_irq_handler(void)
{
PIOS_USART_IRQ_Handler(PIOS_USART_AUX);
PIOS_USART_IRQ_Handler(pios_usart_aux_id);
}
#endif
#ifdef PIOS_COM_SPEKTRUM
void PIOS_USART_spektrum_irq_handler(void)
{
SPEKTRUM_IRQHandler();
}
#endif
#endif /* PIOS_INCLUDE_USART */
#if defined(PIOS_INCLUDE_COM)
#include "pios_com_priv.h"
#endif /* PIOS_INCLUDE_COM */
/**
* Pios servo configuration structures
@ -839,47 +770,6 @@ void PIOS_TIM5_irq_handler()
}
#endif
/*
* COM devices
*/
/*
* Board specific number of devices.
*/
extern const struct pios_com_driver pios_usart_com_driver;
extern const struct pios_com_driver pios_usb_com_driver;
struct pios_com_dev pios_com_devs[] = {
{
.id = PIOS_USART_TELEM,
.driver = &pios_usart_com_driver,
},
{
.id = PIOS_USART_GPS,
.driver = &pios_usart_com_driver,
},
#if defined(PIOS_INCLUDE_USB_HID)
{
.id = 0,
.driver = &pios_usb_com_driver,
},
#endif
#ifdef PIOS_COM_AUX
{
.id = PIOS_USART_AUX,
.driver = &pios_usart_com_driver,
},
#endif
#ifdef PIOS_COM_SPEKTRUM
{
.id = PIOS_USART_AUX,
.driver = &pios_usart_com_driver,
},
#endif
};
const uint8_t pios_com_num_devices = NELEMENTS(pios_com_devs);
/*
* I2C Adapters
*/
@ -1040,6 +930,88 @@ static const struct stm32_gpio pios_debug_pins[] = {
#endif /* PIOS_ENABLE_DEBUG_PINS */
extern const struct pios_com_driver pios_usb_com_driver;
uint32_t pios_com_telem_rf_id;
uint32_t pios_com_telem_usb_id;
uint32_t pios_com_gps_id;
uint32_t pios_com_aux_id;
uint32_t pios_com_spektrum_id;
/**
* PIOS_Board_Init()
* initializes all the core subsystems on this specific hardware
* called from System/openpilot.c
*/
void PIOS_Board_Init(void) {
/* Remap AFIO pin */
//GPIO_PinRemapConfig( GPIO_Remap_SWJ_NoJTRST, ENABLE);
/* Delay system */
PIOS_DELAY_Init();
/* SPI Init */
PIOS_SPI_Init();
/* Enable and mount the SDCard */
PIOS_SDCARD_Init();
PIOS_SDCARD_MountFS(0);
#if defined(PIOS_INCLUDE_SPEKTRUM)
/* SPEKTRUM init must come before comms */
PIOS_SPEKTRUM_Init();
#endif
/* Initialize UAVObject libraries */
EventDispatcherInitialize();
UAVObjInitialize();
UAVObjectsInitializeAll();
/* Initialize the alarms library */
AlarmsInitialize();
/* Initialize the task monitor library */
TaskMonitorInitialize();
/* Initialize the PiOS library */
#if defined(PIOS_INCLUDE_COM)
if (PIOS_USART_Init(&pios_usart_telem_rf_id, &pios_usart_telem_cfg)) {
PIOS_DEBUG_Assert(0);
}
if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_usart_com_driver, pios_usart_telem_rf_id)) {
PIOS_DEBUG_Assert(0);
}
if (PIOS_USART_Init(&pios_usart_gps_id, &pios_usart_gps_cfg)) {
PIOS_DEBUG_Assert(0);
}
if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_gps_id)) {
PIOS_DEBUG_Assert(0);
}
#endif
PIOS_Servo_Init();
PIOS_ADC_Init();
PIOS_GPIO_Init();
#if defined(PIOS_INCLUDE_PWM)
PIOS_PWM_Init();
#endif
#if defined(PIOS_INCLUDE_PPM)
PIOS_PPM_Init();
#endif
#if defined(PIOS_INCLUDE_USB_HID)
PIOS_USB_HID_Init(0);
#if defined(PIOS_INCLUDE_COM)
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_com_driver, 0)) {
PIOS_DEBUG_Assert(0);
}
#endif /* PIOS_INCLUDE_COM */
#endif /* PIOS_INCLUDE_USB_HID */
PIOS_I2C_Init();
PIOS_IAP_Init();
PIOS_WDG_Init();
}
/**
* @}
*/

View File

@ -137,10 +137,19 @@ TIM8 | | | |
//-------------------------
// PIOS_USART
//-------------------------
#define PIOS_USART_MAX_DEVS 2
#define PIOS_USART_RX_BUFFER_SIZE 256
#define PIOS_USART_TX_BUFFER_SIZE 256
#define PIOS_USART_BAUDRATE 230400
#define PIOS_COM_AUX 0
#define PIOS_USART_BAUDRATE 230400
//-------------------------
// PIOS_COM
//
// See also pios_board.c
//-------------------------
#define PIOS_COM_MAX_DEVS 2
extern uint32_t pios_com_aux_id;
#define PIOS_COM_AUX (pios_com_aux_id)
#define PIOS_COM_DEBUG PIOS_COM_AUX
//-------------------------

View File

@ -150,20 +150,36 @@ TIM4 | RC In 1 | Servo 3 | Servo 2 | Servo 1
//-------------------------
// PIOS_USART
//-------------------------
#define PIOS_USART_MAX_DEVS 2
#define PIOS_USART_RX_BUFFER_SIZE 256
#define PIOS_USART_TX_BUFFER_SIZE 256
#define PIOS_USART_BAUDRATE 57600
#define PIOS_COM_DEBUG PIOS_COM_TELEM_RF
#define PIOS_COM_TELEM_RF 0
#ifdef PIOS_INCLUDE_GPS
#define PIOS_COM_GPS 2
#endif
#define PIOS_COM_TELEM_USB 1
//-------------------------
// PIOS_COM
//
// See also pios_board.c
//-------------------------
#define PIOS_COM_MAX_DEVS 4
#define PIOS_COM_TELEM_BAUDRATE 57600
extern uint32_t pios_com_telem_rf_id;
#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id)
#define PIOS_COM_DEBUG PIOS_COM_TELEM_RF
#if defined(PIOS_INCLUDE_GPS)
#define PIOS_COM_GPS_BAUDRATE 57600
extern uint32_t pios_com_gps_id;
#define PIOS_COM_GPS (pios_com_gps_id)
#endif /* PIOS_INCLUDE_GPS */
extern uint32_t pios_com_telem_usb_id;
#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id)
#ifdef PIOS_INCLUDE_SPEKTRUM
#define PIOS_COM_SPEKTRUM_BAUDRATE 115200
#define PIOS_COM_SPEKTRUM 2
#define PIOS_COM_SPEKTRUM_BAUDRATE 115200
extern uint32_t pios_com_spektrum_id;
#define PIOS_COM_SPEKTRUM (pios_com_spektrum_id)
#endif
//-------------------------

View File

@ -164,21 +164,30 @@ TIM8 | | | |
#define PIOS_SPI_PORT 0
// *****************************************************************
//-------------------------
// PIOS_USART
//
// See also pios_board.c
//-------------------------
#define PIOS_USART_MAX_DEVS 1
#define PIOS_USART_RX_BUFFER_SIZE 512
#define PIOS_USART_TX_BUFFER_SIZE 512
#define PIOS_COM_SERIAL 0
//-------------------------
// PIOS_COM
//
// See also pios_board.c
//-------------------------
#define PIOS_COM_MAX_DEVS 2
//#define PIOS_COM_DEBUG PIOS_COM_SERIAL // comment this out if you don't want debug text sent out on the serial port
#define PIOS_USART_BAUDRATE 57600
//#define PIOS_USART_BAUDRATE 115200
extern uint32_t pios_com_serial_id;
#define PIOS_COM_SERIAL (pios_com_serial_id)
//#define PIOS_COM_DEBUG PIOS_COM_SERIAL
#if defined(PIOS_INCLUDE_USB_HID)
#define PIOS_COM_TELEM_USB 1
extern uint32_t pios_com_telem_usb_id;
#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id)
#endif
#if defined(PIOS_COM_DEBUG)

View File

@ -142,34 +142,44 @@ TIM8 | Servo 5 | Servo 6 | Servo 7 | Servo 8
#define PIOS_BMP085_OVERSAMPLING 3
//-------------------------
// USART
// PIOS_USART
//
// See also pios_board.c
//-------------------------
#define PIOS_USART_MAX_DEVS 3
#define PIOS_USART_RX_BUFFER_SIZE 512
#define PIOS_USART_TX_BUFFER_SIZE 512
#define PIOS_COM_TELEM_BAUDRATE 57600
#define PIOS_COM_GPS_BAUDRATE 57600
//-------------------------
// PIOS_COM
//
// See also pios_board.c
//-------------------------
#define PIOS_COM_MAX_DEVS 4
#ifdef PIOS_NO_GPS
#define PIOS_COM_TELEM_RF 0
#define PIOS_COM_TELEM_USB 1
#else
#define PIOS_COM_TELEM_RF 0
#define PIOS_COM_GPS 1
#define PIOS_COM_TELEM_USB 2
#endif
#define PIOS_COM_TELEM_BAUDRATE 57600
extern uint32_t pios_com_telem_rf_id;
#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id)
#define PIOS_COM_GPS_BAUDRATE 57600
extern uint32_t pios_com_gps_id;
#define PIOS_COM_GPS (pios_com_gps_id)
extern uint32_t pios_com_telem_usb_id;
#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id)
#ifdef PIOS_ENABLE_AUX_UART
#define PIOS_COM_AUX_BAUDRATE 57600
#define PIOS_COM_AUX 3
#define PIOS_COM_DEBUG PIOS_COM_AUX
#define PIOS_COM_AUX_BAUDRATE 57600
extern uint32_t pios_com_aux_id;
#define PIOS_COM_AUX (pios_com_aux_id)
#define PIOS_COM_DEBUG PIOS_COM_AUX
#endif
#ifdef PIOS_INCLUDE_SPEKTRUM
#define PIOS_COM_SPEKTRUM_BAUDRATE 115200
#define PIOS_COM_SPEKTRUM 3
#define PIOS_COM_SPEKTRUM_BAUDRATE 115200
extern uint32_t pios_com_spektrum_id;
#define PIOS_COM_SPEKTRUM (pios_com_spektrum_id)
#endif
//-------------------------

View File

@ -36,36 +36,65 @@
#include <pios_com_priv.h>
static struct pios_com_dev *find_com_dev_by_id(uint8_t port)
static bool PIOS_COM_validate(struct pios_com_dev * com_dev)
{
if (port >= pios_com_num_devices) {
/* Undefined COM port for this board (see pios_board.c) */
return NULL;
return (com_dev->magic == PIOS_COM_DEV_MAGIC);
}
#if defined(PIOS_INCLUDE_FREERTOS) && 0
static struct pios_com_dev * PIOS_COM_alloc(void)
{
struct pios_com_dev * com_dev;
com_dev = (struct pios_com_dev *)malloc(sizeof(*com_dev));
if (!com_dev) return (NULL);
com_dev->magic = PIOS_COM_DEV_MAGIC;
return(com_dev);
}
#else
static struct pios_com_dev pios_com_devs[PIOS_COM_MAX_DEVS];
static uint8_t pios_com_num_devs;
static struct pios_com_dev * PIOS_COM_alloc(void)
{
struct pios_com_dev * com_dev;
if (pios_com_num_devs >= PIOS_COM_MAX_DEVS) {
return (NULL);
}
/* Get a handle for the device configuration */
return &(pios_com_devs[port]);
com_dev = &pios_com_devs[pios_com_num_devs++];
com_dev->magic = PIOS_COM_DEV_MAGIC;
return (com_dev);
}
#endif
/**
* Initialises COM layer
* \param[in] mode currently only mode 0 supported
* \param[out] handle
* \param[in] driver
* \param[in] id
* \return < 0 if initialisation failed
*/
int32_t PIOS_COM_Init(void)
int32_t PIOS_COM_Init(uint32_t * com_id, const struct pios_com_driver * driver, const uint32_t lower_id)
{
int32_t ret = 0;
PIOS_DEBUG_Assert(com_id);
PIOS_DEBUG_Assert(driver);
/* If any COM assignment: */
#if defined(PIOS_INCLUDE_USART)
PIOS_USART_Init();
#endif
struct pios_com_dev * com_dev;
#if defined(PIOS_INCLUDE_USB_HID)
PIOS_USB_HID_Init(0);
#endif
com_dev = (struct pios_com_dev *) PIOS_COM_alloc();
if (!com_dev) goto out_fail;
return ret;
com_dev->driver = driver;
com_dev->id = lower_id;
*com_id = (uint32_t)com_dev;
return(0);
out_fail:
return(-1);
}
/**
@ -75,13 +104,11 @@ int32_t PIOS_COM_Init(void)
* \return -1 if port not available
* \return 0 on success
*/
int32_t PIOS_COM_ChangeBaud(uint8_t port, uint32_t baud)
int32_t PIOS_COM_ChangeBaud(uint32_t com_id, uint32_t baud)
{
struct pios_com_dev *com_dev;
struct pios_com_dev * com_dev = (struct pios_com_dev *)com_id;
com_dev = find_com_dev_by_id(port);
if (!com_dev) {
if (!PIOS_COM_validate(com_dev)) {
/* Undefined COM port for this board (see pios_board.c) */
return -1;
}
@ -104,13 +131,11 @@ int32_t PIOS_COM_ChangeBaud(uint8_t port, uint32_t baud)
* caller should retry until buffer is free again
* \return 0 on success
*/
int32_t PIOS_COM_SendBufferNonBlocking(uint8_t port, const uint8_t * buffer, uint16_t len)
int32_t PIOS_COM_SendBufferNonBlocking(uint32_t com_id, const uint8_t *buffer, uint16_t len)
{
struct pios_com_dev *com_dev;
struct pios_com_dev * com_dev = (struct pios_com_dev *)com_id;
com_dev = find_com_dev_by_id(port);
if (!com_dev) {
if (!PIOS_COM_validate(com_dev)) {
/* Undefined COM port for this board (see pios_board.c) */
return -1;
}
@ -132,13 +157,11 @@ int32_t PIOS_COM_SendBufferNonBlocking(uint8_t port, const uint8_t * buffer, uin
* \return -1 if port not available
* \return 0 on success
*/
int32_t PIOS_COM_SendBuffer(uint8_t port, const uint8_t * buffer, uint16_t len)
int32_t PIOS_COM_SendBuffer(uint32_t com_id, const uint8_t *buffer, uint16_t len)
{
struct pios_com_dev *com_dev;
struct pios_com_dev * com_dev = (struct pios_com_dev *)com_id;
com_dev = find_com_dev_by_id(port);
if (!com_dev) {
if (!PIOS_COM_validate(com_dev)) {
/* Undefined COM port for this board (see pios_board.c) */
return -1;
}
@ -160,9 +183,9 @@ int32_t PIOS_COM_SendBuffer(uint8_t port, const uint8_t * buffer, uint16_t len)
* caller should retry until buffer is free again
* \return 0 on success
*/
int32_t PIOS_COM_SendCharNonBlocking(uint8_t port, char c)
int32_t PIOS_COM_SendCharNonBlocking(uint32_t com_id, char c)
{
return PIOS_COM_SendBufferNonBlocking(port, (uint8_t *) & c, 1);
return PIOS_COM_SendBufferNonBlocking(com_id, (uint8_t *)&c, 1);
}
/**
@ -173,9 +196,9 @@ int32_t PIOS_COM_SendCharNonBlocking(uint8_t port, char c)
* \return -1 if port not available
* \return 0 on success
*/
int32_t PIOS_COM_SendChar(uint8_t port, char c)
int32_t PIOS_COM_SendChar(uint32_t com_id, char c)
{
return PIOS_COM_SendBuffer(port, (uint8_t *) & c, 1);
return PIOS_COM_SendBuffer(com_id, (uint8_t *)&c, 1);
}
/**
@ -187,9 +210,9 @@ int32_t PIOS_COM_SendChar(uint8_t port, char c)
* caller should retry until buffer is free again
* \return 0 on success
*/
int32_t PIOS_COM_SendStringNonBlocking(uint8_t port, const char *str)
int32_t PIOS_COM_SendStringNonBlocking(uint32_t com_id, const char *str)
{
return PIOS_COM_SendBufferNonBlocking(port, (uint8_t *) str, (uint16_t) strlen(str));
return PIOS_COM_SendBufferNonBlocking(com_id, (uint8_t *)str, (uint16_t)strlen(str));
}
/**
@ -200,9 +223,9 @@ int32_t PIOS_COM_SendStringNonBlocking(uint8_t port, const char *str)
* \return -1 if port not available
* \return 0 on success
*/
int32_t PIOS_COM_SendString(uint8_t port, const char *str)
int32_t PIOS_COM_SendString(uint32_t com_id, const char *str)
{
return PIOS_COM_SendBuffer(port, (uint8_t *) str, strlen(str));
return PIOS_COM_SendBuffer(com_id, (uint8_t *)str, strlen(str));
}
/**
@ -215,15 +238,15 @@ int32_t PIOS_COM_SendString(uint8_t port, const char *str)
* caller should retry until buffer is free again
* \return 0 on success
*/
int32_t PIOS_COM_SendFormattedStringNonBlocking(uint8_t port, const char *format, ...)
int32_t PIOS_COM_SendFormattedStringNonBlocking(uint32_t com_id, const char *format, ...)
{
uint8_t buffer[128]; // TODO: tmp!!! Provide a streamed COM method later!
uint8_t buffer[128]; // TODO: tmp!!! Provide a streamed COM method later!
va_list args;
va_start(args, format);
vsprintf((char *)buffer, format, args);
return PIOS_COM_SendBufferNonBlocking(port, buffer, (uint16_t) strlen((char *)buffer));
return PIOS_COM_SendBufferNonBlocking(com_id, buffer, (uint16_t)strlen((char *)buffer));
}
/**
@ -235,14 +258,14 @@ int32_t PIOS_COM_SendFormattedStringNonBlocking(uint8_t port, const char *format
* \return -1 if port not available
* \return 0 on success
*/
int32_t PIOS_COM_SendFormattedString(uint8_t port, const char *format, ...)
int32_t PIOS_COM_SendFormattedString(uint32_t com_id, const char *format, ...)
{
uint8_t buffer[128]; // TODO: tmp!!! Provide a streamed COM method later!
uint8_t buffer[128]; // TODO: tmp!!! Provide a streamed COM method later!
va_list args;
va_start(args, format);
vsprintf((char *)buffer, format, args);
return PIOS_COM_SendBuffer(port, buffer, (uint16_t) strlen((char *)buffer));
return PIOS_COM_SendBuffer(com_id, buffer, (uint16_t)strlen((char *)buffer));
}
/**
@ -250,12 +273,15 @@ int32_t PIOS_COM_SendFormattedString(uint8_t port, const char *format, ...)
* \param[in] port COM port
* \returns Byte from buffer
*/
uint8_t PIOS_COM_ReceiveBuffer(uint8_t port)
uint8_t PIOS_COM_ReceiveBuffer(uint32_t com_id)
{
struct pios_com_dev *com_dev;
struct pios_com_dev * com_dev = (struct pios_com_dev *)com_id;
if (!PIOS_COM_validate(com_dev)) {
/* Undefined COM port for this board (see pios_board.c) */
PIOS_DEBUG_Assert(0);
}
com_dev = find_com_dev_by_id(port);
PIOS_DEBUG_Assert(com_dev);
PIOS_DEBUG_Assert(com_dev->driver->rx);
return com_dev->driver->rx(com_dev->id);
@ -266,15 +292,13 @@ uint8_t PIOS_COM_ReceiveBuffer(uint8_t port)
* \param[in] port COM port
* \return Number of bytes used in buffer
*/
int32_t PIOS_COM_ReceiveBufferUsed(uint8_t port)
int32_t PIOS_COM_ReceiveBufferUsed(uint32_t com_id)
{
struct pios_com_dev *com_dev;
struct pios_com_dev * com_dev = (struct pios_com_dev *)com_id;
com_dev = find_com_dev_by_id(port);
if (!com_dev) {
if (!PIOS_COM_validate(com_dev)) {
/* Undefined COM port for this board (see pios_board.c) */
return 0;
PIOS_DEBUG_Assert(0);
}
if (!com_dev->driver->rx_avail) {

View File

@ -37,97 +37,130 @@
#include <pios_usart_priv.h>
/* Provide a COM driver */
static void PIOS_USART_ChangeBaud(uint32_t usart_id, uint32_t baud);
static int32_t PIOS_USART_TxBufferPutMoreNonBlocking(uint32_t usart_id, const uint8_t *buffer, uint16_t len);
static int32_t PIOS_USART_TxBufferPutMore(uint32_t usart_id, const uint8_t *buffer, uint16_t len);
static int32_t PIOS_USART_RxBufferGet(uint32_t usart_id);
static int32_t PIOS_USART_RxBufferUsed(uint32_t usart_id);
const struct pios_com_driver pios_usart_com_driver = {
.set_baud = PIOS_USART_ChangeBaud,
.tx_nb = PIOS_USART_TxBufferPutMoreNonBlocking,
.tx = PIOS_USART_TxBufferPutMore,
.rx = PIOS_USART_RxBufferGet,
.tx_nb = PIOS_USART_TxBufferPutMoreNonBlocking,
.tx = PIOS_USART_TxBufferPutMore,
.rx = PIOS_USART_RxBufferGet,
.rx_avail = PIOS_USART_RxBufferUsed,
};
static struct pios_usart_dev *find_usart_dev_by_id(uint8_t usart)
static bool PIOS_USART_validate(struct pios_usart_dev * usart_dev)
{
if (usart >= pios_usart_num_devices) {
/* Undefined USART port for this board (see pios_board.c) */
return NULL;
}
/* Get a handle for the device configuration */
return &(pios_usart_devs[usart]);
return (usart_dev->magic == PIOS_USART_DEV_MAGIC);
}
/**
* Initialise the onboard USARTs
*/
void PIOS_USART_Init(void)
#if defined(PIOS_INCLUDE_FREERTOS) && 0
static struct pios_usart_dev * PIOS_USART_alloc(void)
{
struct pios_usart_dev *usart_dev;
uint8_t i;
struct pios_usart_dev * usart_dev;
for (i = 0; i < pios_usart_num_devices; i++) {
/* Get a handle for the device configuration */
usart_dev = find_usart_dev_by_id(i);
PIOS_DEBUG_Assert(usart_dev);
usart_dev = (struct pios_usart_dev *)malloc(sizeof(*usart_dev));
if (!usart_dev) return(NULL);
/* Clear buffer counters */
fifoBuf_init(&usart_dev->rx, usart_dev->rx_buffer, sizeof(usart_dev->rx_buffer));
fifoBuf_init(&usart_dev->tx, usart_dev->tx_buffer, sizeof(usart_dev->tx_buffer));
usart_dev->magic = PIOS_USART_DEV_MAGIC;
return(usart_dev);
}
#else
static struct pios_usart_dev pios_usart_devs[PIOS_USART_MAX_DEVS];
static uint8_t pios_usart_num_devs;
static struct pios_usart_dev * PIOS_USART_alloc(void)
{
struct pios_usart_dev * usart_dev;
/* Enable the USART Pins Software Remapping */
if (usart_dev->cfg->remap) {
GPIO_PinRemapConfig(usart_dev->cfg->remap, ENABLE);
}
/* Initialize the USART Rx and Tx pins */
GPIO_Init(usart_dev->cfg->rx.gpio, &usart_dev->cfg->rx.init);
GPIO_Init(usart_dev->cfg->tx.gpio, &usart_dev->cfg->tx.init);
/* Enable USART clock */
switch ((uint32_t) usart_dev->cfg->regs) {
case (uint32_t) USART1:
RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE);
break;
case (uint32_t) USART2:
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE);
break;
case (uint32_t) USART3:
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART3, ENABLE);
break;
}
/* Enable USART */
USART_Init(usart_dev->cfg->regs, &usart_dev->cfg->init);
/* Configure USART Interrupts */
NVIC_Init(&usart_dev->cfg->irq.init);
USART_ITConfig(usart_dev->cfg->regs, USART_IT_RXNE, ENABLE);
USART_ITConfig(usart_dev->cfg->regs, USART_IT_TXE, ENABLE);
/* Enable USART */
USART_Cmd(usart_dev->cfg->regs, ENABLE);
if (pios_usart_num_devs >= PIOS_USART_MAX_DEVS) {
return (NULL);
}
usart_dev = &pios_usart_devs[pios_usart_num_devs++];
usart_dev->magic = PIOS_USART_DEV_MAGIC;
return (usart_dev);
}
#endif
/**
* Initialise a single USART device
*/
int32_t PIOS_USART_Init(uint32_t * usart_id, const struct pios_usart_cfg * cfg)
{
PIOS_DEBUG_Assert(usart_id);
PIOS_DEBUG_Assert(cfg);
struct pios_usart_dev * usart_dev;
usart_dev = (struct pios_usart_dev *) PIOS_USART_alloc();
if (!usart_dev) goto out_fail;
/* Bind the configuration to the device instance */
usart_dev->cfg = cfg;
/* Clear buffer counters */
fifoBuf_init(&usart_dev->rx, usart_dev->rx_buffer, sizeof(usart_dev->rx_buffer));
fifoBuf_init(&usart_dev->tx, usart_dev->tx_buffer, sizeof(usart_dev->tx_buffer));
/* Enable the USART Pins Software Remapping */
if (usart_dev->cfg->remap) {
GPIO_PinRemapConfig(usart_dev->cfg->remap, ENABLE);
}
/* Initialize the USART Rx and Tx pins */
GPIO_Init(usart_dev->cfg->rx.gpio, &usart_dev->cfg->rx.init);
GPIO_Init(usart_dev->cfg->tx.gpio, &usart_dev->cfg->tx.init);
/* Enable USART clock */
switch ((uint32_t)usart_dev->cfg->regs) {
case (uint32_t)USART1:
RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE);
break;
case (uint32_t)USART2:
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE);
break;
case (uint32_t)USART3:
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART3, ENABLE);
break;
}
/* Configure the USART */
USART_Init(usart_dev->cfg->regs, &usart_dev->cfg->init);
*usart_id = (uint32_t)usart_dev;
/* Configure USART Interrupts */
NVIC_Init(&usart_dev->cfg->irq.init);
USART_ITConfig(usart_dev->cfg->regs, USART_IT_RXNE, ENABLE);
USART_ITConfig(usart_dev->cfg->regs, USART_IT_TXE, ENABLE);
/* Enable USART */
USART_Cmd(usart_dev->cfg->regs, ENABLE);
return(0);
out_fail:
return(-1);
}
/**
* Changes the baud rate of the USART peripheral without re-initialising.
* \param[in] usart USART name (GPS, TELEM, AUX)
* \param[in] usart_id USART name (GPS, TELEM, AUX)
* \param[in] baud Requested baud rate
*/
void PIOS_USART_ChangeBaud(uint8_t usart, uint32_t baud)
static void PIOS_USART_ChangeBaud(uint32_t usart_id, uint32_t baud)
{
struct pios_usart_dev *usart_dev;
struct pios_usart_dev * usart_dev = (struct pios_usart_dev *)usart_id;
bool valid = PIOS_USART_validate(usart_dev);
PIOS_Assert(valid)
USART_InitTypeDef USART_InitStructure;
/* Get a handle for the device configuration */
usart_dev = find_usart_dev_by_id(usart);
#if 0
if (!usart_dev) {
/* Undefined USART port for this board (see pios_board.c) */
return -2;
}
#endif
/* Start with a copy of the default configuration for the peripheral */
USART_InitStructure = usart_dev->cfg->init;
@ -138,69 +171,34 @@ void PIOS_USART_ChangeBaud(uint8_t usart, uint32_t baud)
USART_Init(usart_dev->cfg->regs, &USART_InitStructure);
}
/**
* Returns number of free bytes in receive buffer
* \param[in] USART USART name
* \return USART number of free bytes
* \return 1: USART available
* \return 0: USART not available
*/
int32_t PIOS_USART_RxBufferFree(uint8_t usart)
{
struct pios_usart_dev *usart_dev;
/* Get a handle for the device configuration */
usart_dev = find_usart_dev_by_id(usart);
if (!usart_dev) {
/* Undefined USART port for this board (see pios_board.c) */
return -2;
}
return fifoBuf_getFree(&usart_dev->rx);
}
/**
* Returns number of used bytes in receive buffer
* \param[in] USART USART name
* \return > 0: number of used bytes
* \return 0 if USART not available
* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions
*/
int32_t PIOS_USART_RxBufferUsed(uint8_t usart)
static int32_t PIOS_USART_RxBufferUsed(uint32_t usart_id)
{
struct pios_usart_dev *usart_dev;
struct pios_usart_dev * usart_dev = (struct pios_usart_dev *)usart_id;
/* Get a handle for the device configuration */
usart_dev = find_usart_dev_by_id(usart);
bool valid = PIOS_USART_validate(usart_dev);
PIOS_Assert(valid)
if (!usart_dev) {
/* Undefined USART port for this board (see pios_board.c) */
return -2;
}
return fifoBuf_getUsed(&usart_dev->rx);
return (fifoBuf_getUsed(&usart_dev->rx));
}
/**
* Gets a byte from the receive buffer
* \param[in] USART USART name
* \return -1 if USART not available
* \return -2 if no new byte available
* \return >= 0: number of received bytes
* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions
* \return -1 if no new byte available
* \return >= 0: actual byte received
*/
int32_t PIOS_USART_RxBufferGet(uint8_t usart)
static int32_t PIOS_USART_RxBufferGet(uint32_t usart_id)
{
struct pios_usart_dev *usart_dev;
struct pios_usart_dev * usart_dev = (struct pios_usart_dev *)usart_id;
/* Get a handle for the device configuration */
usart_dev = find_usart_dev_by_id(usart);
if (!usart_dev) {
/* Undefined USART port for this board (see pios_board.c) */
return -2;
}
bool valid = PIOS_USART_validate(usart_dev);
PIOS_Assert(valid)
if (fifoBuf_getUsed(&usart_dev->rx) == 0) {
/* Nothing new in the buffer */
@ -208,43 +206,7 @@ int32_t PIOS_USART_RxBufferGet(uint8_t usart)
}
/* get byte - this operation should be atomic! */
/* PIOS_IRQ_Disable(); -- not needed only one reader */
uint8_t b = fifoBuf_getByte(&usart_dev->rx);
/* PIOS_IRQ_Enable(); */
/* Return received byte */
return b;
}
/**
* Returns the next byte of the receive buffer without taking it
* \param[in] USART USART name
* \return -1 if USART not available
* \return -2 if no new byte available
* \return >= 0: number of received bytes
* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions
*/
int32_t PIOS_USART_RxBufferPeek(uint8_t usart)
{
struct pios_usart_dev *usart_dev;
/* Get a handle for the device configuration */
usart_dev = find_usart_dev_by_id(usart);
if (!usart_dev) {
/* Undefined USART port for this board (see pios_board.c) */
return -2;
}
if (!fifoBuf_getUsed(&usart_dev->rx)) {
/* Nothing new in the buffer */
return -1;
}
/* get byte - this operation should be atomic! */
/* PIOS_IRQ_Disable(); -- not needed only one reader */
uint8_t b = fifoBuf_getBytePeek(&usart_dev->rx);
/* PIOS_IRQ_Enable(); */
/* Return received byte */
return b;
@ -255,111 +217,67 @@ int32_t PIOS_USART_RxBufferPeek(uint8_t usart)
* \param[in] USART USART name
* \param[in] b byte which should be put into Rx buffer
* \return 0 if no error
* \return -1 if USART not available
* \return -2 if buffer full (retry)
* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions
* \return -1 if buffer full (retry)
*/
int32_t PIOS_USART_RxBufferPut(uint8_t usart, uint8_t b)
static int32_t PIOS_USART_RxBufferPut(uint32_t usart_id, uint8_t b)
{
struct pios_usart_dev *usart_dev;
struct pios_usart_dev * usart_dev = (struct pios_usart_dev *)usart_id;
/* Get a handle for the device configuration */
usart_dev = find_usart_dev_by_id(usart);
if (!usart_dev) {
/* Undefined USART port for this board (see pios_board.c) */
return -1;
}
bool valid = PIOS_USART_validate(usart_dev);
PIOS_Assert(valid)
if (fifoBuf_getFree(&usart_dev->rx) < 1) {
/* Buffer full (retry) */
return -2;
return -1;
}
/* Copy received byte into receive buffer */
/* This operation should be atomic! */
/* PIOS_IRQ_Disable(); -- not needed only one reader */
fifoBuf_putByte(&usart_dev->rx,b);
/* PIOS_IRQ_Enable(); */
fifoBuf_putByte(&usart_dev->rx, b);
/* No error */
return 0;
}
/**
* returns number of free bytes in transmit buffer
* \param[in] USART USART name
* \return number of free bytes
* \return 0 if USART not available
* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions
*/
int32_t PIOS_USART_TxBufferFree(uint8_t usart)
{
struct pios_usart_dev *usart_dev;
/* Get a handle for the device configuration */
usart_dev = find_usart_dev_by_id(usart);
if (!usart_dev) {
/* Undefined USART port for this board (see pios_board.c) */
return 0;
}
return fifoBuf_getFree(&usart_dev->tx);
}
/**
* returns number of used bytes in transmit buffer
* \param[in] USART USART name
* \return number of used bytes
* \return 0 if USART not available
* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions
*/
int32_t PIOS_USART_TxBufferUsed(uint8_t usart)
static int32_t PIOS_USART_TxBufferUsed(uint32_t usart_id)
{
struct pios_usart_dev *usart_dev;
struct pios_usart_dev * usart_dev = (struct pios_usart_dev *)usart_id;
/* Get a handle for the device configuration */
usart_dev = find_usart_dev_by_id(usart);
bool valid = PIOS_USART_validate(usart_dev);
PIOS_Assert(valid)
if (!usart_dev) {
/* Undefined USART port for this board (see pios_board.c) */
return 0;
}
return fifoBuf_getUsed(&usart_dev->tx);
return (fifoBuf_getUsed(&usart_dev->tx));
}
/**
* gets a byte from the transmit buffer
* \param[in] USART USART name
* \return -1 if USART not available
* \return -2 if no new byte available
* \return -1 if no new byte available
* \return >= 0: transmitted byte
* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions
*/
int32_t PIOS_USART_TxBufferGet(uint8_t usart)
static int32_t PIOS_USART_TxBufferGet(uint32_t usart_id)
{
struct pios_usart_dev *usart_dev;
struct pios_usart_dev * usart_dev = (struct pios_usart_dev *)usart_id;
/* Get a handle for the device configuration */
usart_dev = find_usart_dev_by_id(usart);
if (!usart_dev) {
/* Undefined USART port for this board (see pios_board.c) */
return -1;
}
bool valid = PIOS_USART_validate(usart_dev);
PIOS_Assert(valid)
if (fifoBuf_getUsed(&usart_dev->tx) == 0) {
/* Nothing new in the buffer */
return -2;
return -1;
}
/* get byte - this operation should be atomic! */
PIOS_IRQ_Disable();
PIOS_IRQ_Disable();
uint8_t b = fifoBuf_getByte(&usart_dev->tx);
PIOS_IRQ_Enable();
PIOS_IRQ_Enable();
/* Return received byte */
return b;
}
@ -370,37 +288,32 @@ int32_t PIOS_USART_TxBufferGet(uint8_t usart)
* \param[in] *buffer pointer to buffer to be sent
* \param[in] len number of bytes to be sent
* \return 0 if no error
* \return -1 if USART not available
* \return -2 if buffer full or cannot get all requested bytes (retry)
* \return -3 if USART not supported by USARTTxBufferPut Routine
* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions
* \return -1 if buffer full or cannot get all requested bytes (retry)
*/
int32_t PIOS_USART_TxBufferPutMoreNonBlocking(uint8_t usart, const uint8_t * buffer, uint16_t len)
static int32_t PIOS_USART_TxBufferPutMoreNonBlocking(uint32_t usart_id, const uint8_t *buffer, uint16_t len)
{
struct pios_usart_dev *usart_dev;
struct pios_usart_dev * usart_dev = (struct pios_usart_dev *)usart_id;
/* Get a handle for the device configuration */
usart_dev = find_usart_dev_by_id(usart);
if (!usart_dev) {
/* Undefined USART port for this board (see pios_board.c) */
return -1;
}
bool valid = PIOS_USART_validate(usart_dev);
PIOS_Assert(valid)
if (len >= fifoBuf_getFree(&usart_dev->tx)) {
/* Buffer cannot accept all requested bytes (retry) */
return -2;
return -1;
}
/* Copy bytes to be transmitted into transmit buffer */
/* This operation should be atomic! Can't rely on */
/* fifoBuf since two tasks write to the port */
/* This operation should be atomic! */
PIOS_IRQ_Disable();
uint16_t used = fifoBuf_getUsed(&usart_dev->tx);
fifoBuf_putData(&usart_dev->tx,buffer,len);
if(used == 0) /* enable sending when was empty */
if (used == 0) {
/* enable sending when buffer was previously empty */
USART_ITConfig(usart_dev->cfg->regs, USART_IT_TXE, ENABLE);
}
PIOS_IRQ_Enable();
/* No error */
@ -414,72 +327,38 @@ int32_t PIOS_USART_TxBufferPutMoreNonBlocking(uint8_t usart, const uint8_t * buf
* \param[in] *buffer pointer to buffer to be sent
* \param[in] len number of bytes to be sent
* \return 0 if no error
* \return -1 if USART not available
* \return -3 if USART not supported by USARTTxBufferPut Routine
* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions
*/
int32_t PIOS_USART_TxBufferPutMore(uint8_t usart, const uint8_t * buffer, uint16_t len)
static int32_t PIOS_USART_TxBufferPutMore(uint32_t usart_id, const uint8_t *buffer, uint16_t len)
{
int32_t rc;
while ((rc = PIOS_USART_TxBufferPutMoreNonBlocking(usart, buffer, len)) == -2) ;
while ((rc = PIOS_USART_TxBufferPutMoreNonBlocking(usart_id, buffer, len)) == -1);
return rc;
}
/**
* puts a byte onto the transmit buffer
* \param[in] USART USART name
* \param[in] b byte which should be put into Tx buffer
* \return 0 if no error
* \return -1 if USART not available
* \return -2 if buffer full (retry)
* \return -3 if USART not supported by USARTTxBufferPut Routine
* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions
*/
int32_t PIOS_USART_TxBufferPut_NonBlocking(uint8_t usart, uint8_t b)
void PIOS_USART_IRQ_Handler(uint32_t usart_id)
{
return PIOS_USART_TxBufferPutMoreNonBlocking(usart, &b, 1);
}
struct pios_usart_dev * usart_dev = (struct pios_usart_dev *)usart_id;
/**
* puts a byte onto the transmit buffer<BR>
* (blocking function)
* \param[in] USART USART name
* \param[in] b byte which should be put into Tx buffer
* \return 0 if no error
* \return -1 if USART not available
* \return -3 if USART not supported by USARTTxBufferPut Routine
* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions
*/
int32_t PIOS_USART_TxBufferPut(uint8_t usart, uint8_t b)
{
return PIOS_USART_TxBufferPutMore(usart, &b, 1);
}
bool valid = PIOS_USART_validate(usart_dev);
PIOS_Assert(valid)
void PIOS_USART_IRQ_Handler(uint8_t usart)
{
struct pios_usart_dev *usart_dev;
/* Get a handle for the device configuration */
usart_dev = find_usart_dev_by_id(usart);
PIOS_DEBUG_Assert(usart_dev);
/* Force read of dr after sr to make sure to clear error flags */
volatile uint16_t sr = usart_dev->cfg->regs->SR;
volatile uint8_t dr = usart_dev->cfg->regs->DR;
/* Check if RXNE flag is set */
if (sr & USART_SR_RXNE) {
if (PIOS_USART_RxBufferPut(usart, dr) < 0) {
if (PIOS_USART_RxBufferPut(usart_id, dr) < 0) {
/* Here we could add some error handling */
}
}
/* Check if TXE flag is set */
if (sr & USART_SR_TXE) {
if (PIOS_USART_TxBufferUsed(usart) > 0) {
int32_t b = PIOS_USART_TxBufferGet(usart);
if (PIOS_USART_TxBufferUsed(usart_id) > 0) {
int32_t b = PIOS_USART_TxBufferGet(usart_id);
if (b < 0) {
/* Here we could add some error handling */

View File

@ -44,6 +44,11 @@
#define USE_FREERTOS
#endif
static int32_t PIOS_USB_HID_TxBufferPutMoreNonBlocking(uint32_t usbcom_id, const uint8_t *buffer, uint16_t len);
static int32_t PIOS_USB_HID_TxBufferPutMore(uint32_t usbcom_id, const uint8_t *buffer, uint16_t len);
static int32_t PIOS_USB_HID_RxBufferGet(uint32_t usbcom_id);
static int32_t PIOS_USB_HID_RxBufferUsed(uint32_t usbcom_id);
const struct pios_com_driver pios_usb_com_driver = {
.tx_nb = PIOS_USB_HID_TxBufferPutMoreNonBlocking,
.tx = PIOS_USB_HID_TxBufferPutMore,
@ -201,7 +206,6 @@ void sendChunk()
uint32_t size = fifoBuf_getUsed(&tx_pios_fifo_buffer);
if ((size > 0) && (GetEPTxStatus(ENDP1) != EP_TX_VALID)) {
if (size > PIOS_USB_HID_DATA_LENGTH)
size = PIOS_USB_HID_DATA_LENGTH;
#ifdef USB_HID
@ -219,7 +223,7 @@ void sendChunk()
/* Send Buffer */
SetEPTxValid(ENDP1);
}
}
}
@ -232,13 +236,13 @@ void sendChunk()
* \return -2 if too many bytes to be send
* \note Applications shouldn't call this function directly, instead please use \ref PIOS_COM layer functions
*/
int32_t PIOS_USB_HID_TxBufferPutMoreNonBlocking(uint8_t id, const uint8_t * buffer, uint16_t len)
static int32_t PIOS_USB_HID_TxBufferPutMoreNonBlocking(uint32_t usbcom_id, const uint8_t * buffer, uint16_t len)
{
uint16_t ret;
if(!transfer_possible)
return -1;
return -1;
if (len > fifoBuf_getFree(&tx_pios_fifo_buffer)) {
sendChunk(); /* Try and send what's in the buffer though */
return -2; /* Cannot send all requested bytes */
@ -257,7 +261,7 @@ int32_t PIOS_USB_HID_TxBufferPutMoreNonBlocking(uint8_t id, const uint8_t * buff
#if defined(USE_FREERTOS)
xSemaphoreGive(pios_usb_tx_semaphore);
#endif
sendChunk();
return 0;
@ -272,13 +276,13 @@ int32_t PIOS_USB_HID_TxBufferPutMoreNonBlocking(uint8_t id, const uint8_t * buff
* \return -1 if too many bytes to be send
* \note Applications shouldn't call this function directly, instead please use \ref PIOS_COM layer functions
*/
int32_t PIOS_USB_HID_TxBufferPutMore(uint8_t id, const uint8_t * buffer, uint16_t len)
static int32_t PIOS_USB_HID_TxBufferPutMore(uint32_t usbcom_id, const uint8_t *buffer, uint16_t len)
{
if(len > (fifoBuf_getUsed(&tx_pios_fifo_buffer) + fifoBuf_getFree(&tx_pios_fifo_buffer)))
return -1;
uint32_t error;
while ((error = PIOS_USB_HID_TxBufferPutMoreNonBlocking(id, buffer, len)) == -2) {
while ((error = PIOS_USB_HID_TxBufferPutMoreNonBlocking(usbcom_id, buffer, len)) == -2) {
#if defined(PIOS_INCLUDE_FREERTOS)
taskYIELD();
#endif
@ -293,15 +297,15 @@ int32_t PIOS_USB_HID_TxBufferPutMore(uint8_t id, const uint8_t * buffer, uint16_
* \return >= 0: received byte
* \note Applications shouldn't call this function directly, instead please use \ref PIOS_COM layer functions
*/
int32_t PIOS_USB_HID_RxBufferGet(uint8_t id)
static int32_t PIOS_USB_HID_RxBufferGet(uint32_t usbcom_id)
{
uint8_t read;
if(fifoBuf_getUsed(&rx_pios_fifo_buffer) == 0)
return -1;
read = fifoBuf_getByte(&rx_pios_fifo_buffer);
// If endpoint was stalled and there is now space make it valid
if ((GetEPRxStatus(ENDP1) != EP_RX_VALID) && (fifoBuf_getFree(&rx_pios_fifo_buffer) > 62)) {
SetEPRxStatus(ENDP1, EP_RX_VALID);
@ -315,7 +319,7 @@ int32_t PIOS_USB_HID_RxBufferGet(uint8_t id)
* \return 0 nothing available
* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions
*/
int32_t PIOS_USB_HID_RxBufferUsed(uint8_t id)
static int32_t PIOS_USB_HID_RxBufferUsed(uint32_t usbcom_id)
{
return fifoBuf_getUsed(&rx_pios_fifo_buffer);
}
@ -342,14 +346,14 @@ void PIOS_USB_HID_EP1_OUT_Callback(void)
/* Use the memory interface function to write to the selected endpoint */
PMAToUserBufferCopy((uint8_t *) &rx_packet_buffer[0], GetEPRxAddr(ENDP1 & 0x7F), DataLength);
/* The first byte is report ID (not checked), the second byte is the valid data length */
#ifdef USB_HID
fifoBuf_putData(&rx_pios_fifo_buffer, &rx_packet_buffer[1], PIOS_USB_HID_DATA_LENGTH + 1);
#else
fifoBuf_putData(&rx_pios_fifo_buffer, &rx_packet_buffer[2], rx_packet_buffer[1]);
#endif
// Only reactivate endpoint if available space in buffer
if (fifoBuf_getFree(&rx_pios_fifo_buffer) > 62) {
SetEPRxStatus(ENDP1, EP_RX_VALID);

View File

@ -32,31 +32,29 @@
#ifndef PIOS_COM_H
#define PIOS_COM_H
/* Public Functions */
extern int32_t PIOS_COM_Init(void);
extern int32_t PIOS_COM_ChangeBaud(uint8_t port, uint32_t baud);
extern int32_t PIOS_COM_SendCharNonBlocking(uint8_t port, char c);
extern int32_t PIOS_COM_SendChar(uint8_t port, char c);
extern int32_t PIOS_COM_SendBufferNonBlocking(uint8_t port, const uint8_t * buffer, uint16_t len);
extern int32_t PIOS_COM_SendBuffer(uint8_t port, const uint8_t * buffer, uint16_t len);
extern int32_t PIOS_COM_SendStringNonBlocking(uint8_t port, const char *str);
extern int32_t PIOS_COM_SendString(uint8_t port, const char *str);
extern int32_t PIOS_COM_SendFormattedStringNonBlocking(uint8_t port, const char *format, ...);
extern int32_t PIOS_COM_SendFormattedString(uint8_t port, const char *format, ...);
extern uint8_t PIOS_COM_ReceiveBuffer(uint8_t port);
extern int32_t PIOS_COM_ReceiveBufferUsed(uint8_t port);
extern int32_t PIOS_COM_ReceiveHandler(void);
struct pios_com_driver {
void (*init) (uint8_t id);
void (*set_baud) (uint8_t id, uint32_t baud);
int32_t(*tx_nb) (uint8_t id, const uint8_t * buffer, uint16_t len);
int32_t(*tx) (uint8_t id, const uint8_t * buffer, uint16_t len);
int32_t(*rx) (uint8_t id);
int32_t(*rx_avail) (uint8_t id);
void (*init)(uint32_t id);
void (*set_baud)(uint32_t id, uint32_t baud);
int32_t (*tx_nb)(uint32_t id, const uint8_t *buffer, uint16_t len);
int32_t (*tx)(uint32_t id, const uint8_t *buffer, uint16_t len);
int32_t (*rx)(uint32_t id);
int32_t (*rx_avail)(uint32_t id);
};
/* Public Functions */
extern int32_t PIOS_COM_Init(uint32_t * com_id, const struct pios_com_driver * driver, const uint32_t lower_id);
extern int32_t PIOS_COM_ChangeBaud(uint32_t com_id, uint32_t baud);
extern int32_t PIOS_COM_SendCharNonBlocking(uint32_t com_id, char c);
extern int32_t PIOS_COM_SendChar(uint32_t com_id, char c);
extern int32_t PIOS_COM_SendBufferNonBlocking(uint32_t com_id, const uint8_t *buffer, uint16_t len);
extern int32_t PIOS_COM_SendBuffer(uint32_t com_id, const uint8_t *buffer, uint16_t len);
extern int32_t PIOS_COM_SendStringNonBlocking(uint32_t com_id, const char *str);
extern int32_t PIOS_COM_SendString(uint32_t com_id, const char *str);
extern int32_t PIOS_COM_SendFormattedStringNonBlocking(uint32_t com_id, const char *format, ...);
extern int32_t PIOS_COM_SendFormattedString(uint32_t com_id, const char *format, ...);
extern uint8_t PIOS_COM_ReceiveBuffer(uint32_t com_id);
extern int32_t PIOS_COM_ReceiveBufferUsed(uint32_t com_id);
#endif /* PIOS_COM_H */
/**

View File

@ -34,13 +34,17 @@
#include <pios.h>
struct pios_com_dev {
uint8_t id;
const struct pios_com_driver *const driver;
enum pios_com_dev_magic {
PIOS_COM_DEV_MAGIC = 0xaa55aa55,
};
extern struct pios_com_dev pios_com_devs[];
extern const uint8_t pios_com_num_devices;
struct pios_com_dev {
enum pios_com_dev_magic magic;
uint32_t id;
const struct pios_com_driver * driver;
};
extern int32_t PIOS_COM_ReceiveHandler(uint32_t com_id);
#endif /* PIOS_COM_PRIV_H */

View File

@ -40,8 +40,10 @@ void PIOS_DEBUG_Panic(const char *msg);
#ifdef DEBUG
#define PIOS_DEBUG_Assert(test) if (!(test)) PIOS_DEBUG_Panic(PIOS_DEBUG_AssertMsg);
#define PIOS_Assert(test) PIOS_DEBUG_Assert(test)
#else
#define PIOS_DEBUG_Assert(test)
#define PIOS_Assert(test) if (!(test)) while (1);
#endif
#endif /* PIOS_DEBUG_H */

View File

@ -32,26 +32,11 @@
#ifndef PIOS_USART_H
#define PIOS_USART_H
#include <pios_stm32.h>
/* Global Types */
/* Public Functions */
extern void PIOS_USART_Init(void);
extern void PIOS_USART_ChangeBaud(uint8_t usart, uint32_t baud);
extern int32_t PIOS_USART_RxBufferFree(uint8_t usart);
extern int32_t PIOS_USART_RxBufferUsed(uint8_t usart);
extern int32_t PIOS_USART_RxBufferGet(uint8_t usart);
extern int32_t PIOS_USART_RxBufferPeek(uint8_t usart);
extern int32_t PIOS_USART_RxBufferPut(uint8_t usart, uint8_t b);
extern int32_t PIOS_USART_TxBufferFree(uint8_t usart);
extern int32_t PIOS_USART_TxBufferGet(uint8_t usart);
extern int32_t PIOS_USART_TxBufferPutMoreNonBlocking(uint8_t usart, const uint8_t * buffer, uint16_t len);
extern int32_t PIOS_USART_TxBufferPutMore(uint8_t usart, const uint8_t * buffer, uint16_t len);
extern int32_t PIOS_USART_TxBufferPutNonBlocking(uint8_t usart, uint8_t b);
extern int32_t PIOS_USART_TxBufferPut(uint8_t usart, uint8_t b);
extern void PIOS_USART_IRQ_Handler(uint8_t usart);
#endif /* PIOS_USART_H */
/**

View File

@ -34,7 +34,10 @@
#include <pios.h>
#include <pios_stm32.h>
#include <fifo_buffer.h>
#include "fifo_buffer.h"
#include "pios_usart.h"
extern const struct pios_com_driver pios_usart_com_driver;
struct pios_usart_cfg {
USART_TypeDef *regs;
@ -45,18 +48,26 @@ struct pios_usart_cfg {
struct stm32_irq irq;
};
struct pios_usart_dev {
const struct pios_usart_cfg *const cfg;
enum pios_usart_dev_magic {
PIOS_USART_DEV_MAGIC = 0x11223344,
};
uint8_t rx_buffer[PIOS_USART_RX_BUFFER_SIZE] __attribute__ ((aligned(4))); // align to 32-bit to try and provide speed improvement;
struct pios_usart_dev {
enum pios_usart_dev_magic magic;
const struct pios_usart_cfg * cfg;
// align to 32-bit to try and provide speed improvement;
uint8_t rx_buffer[PIOS_USART_RX_BUFFER_SIZE] __attribute__ ((aligned(4)));
t_fifo_buffer rx;
uint8_t tx_buffer[PIOS_USART_TX_BUFFER_SIZE] __attribute__ ((aligned(4))); // align to 32-bit to try and provide speed improvement;
// align to 32-bit to try and provide speed improvement;
uint8_t tx_buffer[PIOS_USART_TX_BUFFER_SIZE] __attribute__ ((aligned(4)));
t_fifo_buffer tx;
};
extern struct pios_usart_dev pios_usart_devs[];
extern uint8_t pios_usart_num_devices;
extern int32_t PIOS_USART_Init(uint32_t * usart_id, const struct pios_usart_cfg * cfg);
extern void PIOS_USART_IRQ_Handler(uint32_t usart_id);
#endif /* PIOS_USART_PRIV_H */

View File

@ -45,10 +45,7 @@ extern int32_t PIOS_USB_HID_Init(uint32_t mode);
extern int32_t PIOS_USB_HID_Reenumerate();
extern int32_t PIOS_USB_HID_ChangeConnectionState(uint32_t Connected);
extern int32_t PIOS_USB_HID_CheckAvailable(uint8_t id);
extern int32_t PIOS_USB_HID_TxBufferPutMoreNonBlocking(uint8_t id, const uint8_t * buffer, uint16_t len);
extern int32_t PIOS_USB_HID_TxBufferPutMore(uint8_t id, const uint8_t * buffer, uint16_t len);
extern int32_t PIOS_USB_HID_RxBufferGet(uint8_t id);
extern int32_t PIOS_USB_HID_RxBufferUsed(uint8_t id);
extern int32_t PIOS_USB_HID_CB_Data_Setup(uint8_t RequestNo);
extern int32_t PIOS_USB_HID_CB_NoData_Setup(uint8_t RequestNo);
extern void PIOS_USB_HID_EP1_IN_Callback(void);

View File

@ -50,6 +50,9 @@
#include "main.h"
/* Prototype of PIOS_Board_Init() function */
extern void PIOS_Board_Init(void);
// *****************************************************************************
// ADC data
@ -589,33 +592,13 @@ int main()
saved_settings.frequency_band = FREQBAND_UNKNOWN;
// *************
// Bring up System using CMSIS functions, enables the LEDs.
PIOS_SYS_Init();
// turn all the leds on
USB_LED_ON;
LINK_LED_ON;
RX_LED_ON;
TX_LED_ON;
PIOS_Board_Init();
CRC_init();
// read the CPU details
get_CPUDetails();
// Delay system
PIOS_DELAY_Init();
// UART communication system
PIOS_COM_Init();
// ADC system
// PIOS_ADC_Init();
// SPI link to master
PIOS_SPI_Init();
// setup the GPIO input pins
GPIO_IN_Init();

View File

@ -250,6 +250,7 @@ void PIOS_ADC_handler() {
// USART
#if defined(PIOS_INCLUDE_USART)
#include <pios_usart_priv.h>
/*
@ -263,11 +264,7 @@ const struct pios_usart_cfg pios_usart_serial_cfg =
.regs = USART1,
.init =
{
#if defined(PIOS_USART_BAUDRATE)
.USART_BaudRate = PIOS_USART_BAUDRATE,
#else
.USART_BaudRate = 57600,
#endif
.USART_BaudRate = 57600,
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1,
@ -307,22 +304,10 @@ const struct pios_usart_cfg pios_usart_serial_cfg =
},
};
/*
* Board specific number of devices.
*/
struct pios_usart_dev pios_usart_devs[] =
{
#define PIOS_USART_SERIAL 0
{
.cfg = &pios_usart_serial_cfg,
},
};
uint8_t pios_usart_num_devices = NELEMENTS(pios_usart_devs);
static uint32_t pios_usart_serial_id;
void PIOS_USART_serial_irq_handler(void)
{
PIOS_USART_IRQ_Handler(PIOS_USART_SERIAL);
PIOS_USART_IRQ_Handler(pios_usart_serial_id);
}
#endif /* PIOS_INCLUDE_USART */
@ -330,36 +315,55 @@ void PIOS_USART_serial_irq_handler(void)
// ***********************************************************************************
#if defined(PIOS_INCLUDE_COM)
#include <pios_com_priv.h>
/*
* COM devices
*/
/*
* Board specific number of devices.
*/
extern const struct pios_com_driver pios_usart_com_driver;
#if defined(PIOS_INCLUDE_USB_HID)
extern const struct pios_com_driver pios_usb_com_driver;
#endif
struct pios_com_dev pios_com_devs[] =
{
{
.id = PIOS_USART_SERIAL,
.driver = &pios_usart_com_driver,
},
#if defined(PIOS_INCLUDE_USB_HID)
{
.id = 0,
.driver = &pios_usb_com_driver,
},
#endif
};
const uint8_t pios_com_num_devices = NELEMENTS(pios_com_devs);
#endif /* PIOS_INCLUDE_COM */
// ***********************************************************************************
extern const struct pios_com_driver pios_usb_com_driver;
uint32_t pios_com_serial_id;
uint32_t pios_com_telem_usb_id;
/**
* PIOS_Board_Init()
* initializes all the core subsystems on this specific hardware
* called from System/openpilot.c
*/
void PIOS_Board_Init(void) {
// Bring up System using CMSIS functions, enables the LEDs.
PIOS_SYS_Init();
// turn all the leds on
USB_LED_ON;
LINK_LED_ON;
RX_LED_ON;
TX_LED_ON;
// Delay system
PIOS_DELAY_Init();
if (PIOS_USART_Init(&pios_usart_serial_id, &pios_usart_serial_cfg)) {
PIOS_DEBUG_Assert(0);
}
if (PIOS_COM_Init(&pios_com_serial_id, &pios_usart_com_driver, pios_usart_serial_id)) {
PIOS_DEBUG_Assert(0);
}
#if defined(PIOS_INCLUDE_USB_HID)
PIOS_USB_HID_Init(0);
#if defined(PIOS_INCLUDE_COM)
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_com_driver, 0)) {
PIOS_DEBUG_Assert(0);
}
#endif /* PIOS_INCLUDE_COM */
#endif /* PIOS_INCLUDE_USB_HID */
// ADC system
// PIOS_ADC_Init();
// SPI link to master
PIOS_SPI_Init();
}