mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-02-20 10:54:14 +01:00
LP-512 Initial F3 support
This commit is contained in:
parent
a2d8d795d6
commit
5435dbd464
1
Makefile
1
Makefile
@ -340,6 +340,7 @@ PACKAGE_FW_TARGETS += fw_oplinkmini
|
||||
PACKAGE_FW_TARGETS += fw_gpsplatinum
|
||||
PACKAGE_FW_TARGETS += fw_osd
|
||||
PACKAGE_FW_TARGETS += fw_revoproto
|
||||
PACKAGE_FW_TARGETS += fw_spracingf3evo fw_spracingf3
|
||||
|
||||
# Rules to generate GCS resources used to embed firmware binaries into the GCS.
|
||||
# They are used later by the vehicle setup wizard to update board firmware.
|
||||
|
@ -14,12 +14,16 @@ ALL_BOARDS += oplinkmini
|
||||
ALL_BOARDS += gpsplatinum
|
||||
ALL_BOARDS += osd
|
||||
ALL_BOARDS += discoveryf4bare
|
||||
ALL_BOARDS += ccf3d spracingf3 spracingf3evo
|
||||
# SimPosix only builds on Linux
|
||||
ifeq ($(UNAME), Linux)
|
||||
ALL_BOARDS += simposix
|
||||
endif
|
||||
|
||||
# Short names of each board (used to display board name in parallel builds)
|
||||
spracingf3_short := 'srf3'
|
||||
spracingf3evo_short := 'spev'
|
||||
ccf3d_short := 'cf3d'
|
||||
coptercontrol_short := 'cc '
|
||||
oplinkmini_short := 'oplm'
|
||||
revolution_short := 'revo'
|
||||
|
@ -54,14 +54,16 @@ include $(FREERTOS_DIR)/library.mk
|
||||
OPTESTS = $(TOPDIR)/Tests
|
||||
|
||||
## PIOS Hardware
|
||||
ifeq ($(MCU),cortex-m3)
|
||||
ifneq (,$(findstring STM32F10,$(CHIP)))
|
||||
include $(PIOS)/stm32f10x/library.mk
|
||||
else ifeq ($(MCU),cortex-m4)
|
||||
else ifneq (,$(findstring STM32F4,$(CHIP)))
|
||||
include $(PIOS)/stm32f4xx/library.mk
|
||||
else ifeq ($(MCU),cortex-m0)
|
||||
else ifneq (,$(findstring STM32F30,$(CHIP)))
|
||||
include $(PIOS)/stm32f30x/library.mk
|
||||
else ifneq (,$(findstring STM32F0,$(CHIP)))
|
||||
include $(PIOS)/stm32f0x/library.mk
|
||||
else
|
||||
$(error Unsupported MCU: $(MCU))
|
||||
$(error Unsupported CHIP: $(CHIP))
|
||||
endif
|
||||
|
||||
# List C source files here (C dependencies are automatically generated).
|
||||
|
@ -34,14 +34,16 @@ FLIGHTLIBINC = $(FLIGHTLIB)/inc
|
||||
override USE_DSP_LIB := NO
|
||||
|
||||
## PIOS Hardware
|
||||
ifeq ($(MCU),cortex-m3)
|
||||
ifneq (,$(findstring STM32F10,$(CHIP)))
|
||||
include $(PIOS)/stm32f10x/library.mk
|
||||
else ifeq ($(MCU),cortex-m4)
|
||||
else ifneq (,$(findstring STM32F4,$(CHIP)))
|
||||
include $(PIOS)/stm32f4xx/library.mk
|
||||
else ifeq ($(MCU),cortex-m0)
|
||||
else ifneq (,$(findstring STM32F30,$(CHIP)))
|
||||
include $(PIOS)/stm32f30x/library.mk
|
||||
else ifneq (,$(findstring STM32F0,$(CHIP)))
|
||||
include $(PIOS)/stm32f0x/library.mk
|
||||
else
|
||||
$(error Unsupported MCU: $(MCU))
|
||||
$(error Unsupported CHIP: $(CHIP))
|
||||
endif
|
||||
|
||||
# List C source files here (C dependencies are automatically generated).
|
||||
|
@ -87,11 +87,10 @@ int32_t BatteryInitialize(void)
|
||||
batteryEnabled = true;
|
||||
#else
|
||||
HwSettingsInitialize();
|
||||
uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM];
|
||||
HwSettingsOptionalModulesData optionalModules;
|
||||
HwSettingsOptionalModulesGet(&optionalModules);
|
||||
|
||||
HwSettingsOptionalModulesGet(optionalModules);
|
||||
|
||||
if ((optionalModules[HWSETTINGS_OPTIONALMODULES_BATTERY] == HWSETTINGS_OPTIONALMODULES_ENABLED)) {
|
||||
if (optionalModules.Battery == HWSETTINGS_OPTIONALMODULES_ENABLED) {
|
||||
batteryEnabled = true;
|
||||
} else {
|
||||
batteryEnabled = false;
|
||||
@ -149,17 +148,19 @@ static void onTimer(__attribute__((unused)) UAVObjEvent *ev)
|
||||
batterySettings.ResetConsumedEnergy = false;
|
||||
FlightBatterySettingsSet(&batterySettings);
|
||||
}
|
||||
|
||||
#ifdef PIOS_INCLUDE_ADC
|
||||
// calculate the battery parameters
|
||||
if (voltageADCPin >= 0) {
|
||||
flightBatteryData.Voltage = (PIOS_ADC_PinGetVolt(voltageADCPin) - batterySettings.SensorCalibrations.VoltageZero) * batterySettings.SensorCalibrations.VoltageFactor; // in Volts
|
||||
} else {
|
||||
flightBatteryData.Voltage = 0; // Dummy placeholder value. This is in case we get another source of battery current which is not from the ADC
|
||||
}
|
||||
|
||||
#else
|
||||
flightBatteryData.Voltage = 0;
|
||||
#endif /* PIOS_INCLUDE_ADC */
|
||||
// voltage available: get the number of cells if possible, desired and not armed
|
||||
GetNbCells(&batterySettings, &flightBatteryData);
|
||||
|
||||
#ifdef PIOS_INCLUDE_ADC
|
||||
// ad a plausibility check: zero voltage => zero current
|
||||
if (currentADCPin >= 0 && flightBatteryData.Voltage > 0.f) {
|
||||
flightBatteryData.Current = (PIOS_ADC_PinGetVolt(currentADCPin) - batterySettings.SensorCalibrations.CurrentZero) * batterySettings.SensorCalibrations.CurrentFactor; // in Amps
|
||||
@ -169,6 +170,9 @@ static void onTimer(__attribute__((unused)) UAVObjEvent *ev)
|
||||
} else { // If there's no current measurement, we still need to assign one. Make it negative, so it can never trigger an alarm
|
||||
flightBatteryData.Current = -0; // Dummy placeholder value. This is in case we get another source of battery current which is not from the ADC
|
||||
}
|
||||
#else
|
||||
flightBatteryData.Current = -0;
|
||||
#endif /* PIOS_INCLUDE_ADC */
|
||||
|
||||
// For safety reasons consider only positive currents in energy comsumption, i.e. no charging up.
|
||||
// necesary when sensor are not perfectly calibrated
|
||||
|
@ -63,7 +63,6 @@
|
||||
#include <auxmagsupport.h>
|
||||
#include <accelgyrosettings.h>
|
||||
#include <revosettings.h>
|
||||
#include <UBX.h>
|
||||
|
||||
#include <mathmisc.h>
|
||||
#include <taskinfo.h>
|
||||
@ -284,7 +283,7 @@ static void SensorsTask(__attribute__((unused)) void *parameters)
|
||||
count++;
|
||||
}
|
||||
|
||||
PIOS_Assert(count);
|
||||
// PIOS_Assert(count);
|
||||
RELOAD_WDG();
|
||||
if (!sensors_test) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_SENSORS, SYSTEMALARMS_ALARM_CRITICAL);
|
||||
|
@ -165,6 +165,12 @@ static float gyroRaw[3];
|
||||
static float gyroDelta[3];
|
||||
|
||||
// preconfigured filter chains selectable via revoSettings.FusionAlgorithm
|
||||
|
||||
static const filterPipeline *acroQueue = &(filterPipeline) {
|
||||
.filter = &cfFilter,
|
||||
.next = NULL,
|
||||
};
|
||||
|
||||
static const filterPipeline *cfQueue = &(filterPipeline) {
|
||||
.filter = &airFilter,
|
||||
.next = &(filterPipeline) {
|
||||
@ -434,6 +440,9 @@ static void StateEstimationCb(void)
|
||||
if (fsarmed == FLIGHTSTATUS_ARMED_DISARMED || fusionAlgorithm == FILTER_INIT_FORCE) {
|
||||
const filterPipeline *newFilterChain;
|
||||
switch ((RevoSettingsFusionAlgorithmOptions)revoSettings.FusionAlgorithm) {
|
||||
case REVOSETTINGS_FUSIONALGORITHM_ACRONOSENSORS:
|
||||
newFilterChain = acroQueue;
|
||||
break;
|
||||
case REVOSETTINGS_FUSIONALGORITHM_BASICCOMPLEMENTARY:
|
||||
newFilterChain = cfQueue;
|
||||
// reinit Mag alarm
|
||||
|
@ -579,7 +579,11 @@ static uint16_t GetFreeIrqStackSize(void)
|
||||
#if !defined(ARCH_POSIX) && !defined(ARCH_WIN32) && defined(CHECK_IRQ_STACK)
|
||||
extern uint32_t _irq_stack_top;
|
||||
extern uint32_t _irq_stack_end;
|
||||
uint32_t pattern = 0x0000A5A5;
|
||||
#ifdef STM32F3
|
||||
uint32_t pattern = 0xA5A5A5A5;
|
||||
#else
|
||||
uint32_t pattern = 0xA5A5;
|
||||
#endif
|
||||
uint32_t *ptr = &_irq_stack_end;
|
||||
|
||||
#if 1 /* the ugly way accurate but takes more time, useful for debugging */
|
||||
|
20
flight/pios/common/libraries/FreeRTOS/Source/openocd.c
Normal file
20
flight/pios/common/libraries/FreeRTOS/Source/openocd.c
Normal file
@ -0,0 +1,20 @@
|
||||
/*
|
||||
* Since at least FreeRTOS V7.5.3 uxTopUsedPriority is no longer
|
||||
* present in the kernel, so it has to be supplied by other means for
|
||||
* OpenOCD's threads awareness.
|
||||
*
|
||||
* Add this file to your project, and, if you're using --gc-sections,
|
||||
* ``--undefined=uxTopUsedPriority'' (or
|
||||
* ``-Wl,--undefined=uxTopUsedPriority'' when using gcc for final
|
||||
* linking) to your LDFLAGS; same with all the other symbols you need.
|
||||
*/
|
||||
|
||||
#include "FreeRTOS.h"
|
||||
|
||||
#ifdef __GNUC__
|
||||
#define USED __attribute__((section(".keep")))
|
||||
#else
|
||||
#define USED
|
||||
#endif
|
||||
|
||||
const int USED uxTopUsedPriority = configMAX_PRIORITIES;
|
@ -81,6 +81,9 @@ pios_general_malloc(void *ptr, size_t s, bool use_fast_heap)
|
||||
vPortEnterCritical();
|
||||
if(use_fast_heap){
|
||||
p = msheap_alloc(&fast_heap, ptr, s);
|
||||
if(!p) {
|
||||
p = msheap_alloc(&sram_heap, ptr, s);
|
||||
}
|
||||
} else {
|
||||
p = msheap_alloc(&sram_heap, ptr, s);
|
||||
}
|
||||
|
@ -233,7 +233,7 @@ void PIOS_BOARD_IO_Configure_USB_Function(PIOS_BOARD_IO_USB_HID_Function hid_fun
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB_HID */
|
||||
|
||||
#ifndef STM32F10X
|
||||
#if !defined(STM32F1) && !defined(STM32F3)
|
||||
PIOS_USBHOOK_Activate();
|
||||
#endif
|
||||
}
|
||||
@ -672,7 +672,6 @@ void PIOS_BOARD_IO_Configure_RFM22B()
|
||||
OPLinkStatusSet(&oplinkStatus);
|
||||
}
|
||||
|
||||
|
||||
void PIOS_BOARD_IO_Configure_RadioAuxStream(HwSettingsRadioAuxStreamOptions radioaux)
|
||||
{
|
||||
switch (radioaux) {
|
||||
|
@ -42,6 +42,10 @@
|
||||
# include <pios_ms5611.h>
|
||||
#endif
|
||||
|
||||
#ifdef PIOS_INCLUDE_BMP280
|
||||
# include <pios_bmp280.h>
|
||||
#endif
|
||||
|
||||
#ifdef PIOS_INCLUDE_ADXL345
|
||||
# include <pios_adxl345.h>
|
||||
#endif
|
||||
@ -75,7 +79,13 @@ void PIOS_BOARD_Sensors_Configure()
|
||||
#ifdef PIOS_INCLUDE_MPU6000
|
||||
const struct pios_mpu6000_cfg *mpu6000_cfg = PIOS_BOARD_HW_DEFS_GetMPU6000Cfg(pios_board_info_blob.board_rev);
|
||||
if (mpu6000_cfg) {
|
||||
#ifdef PIOS_SPI_MPU6000_ADAPTER
|
||||
PIOS_MPU6000_Init(PIOS_SPI_MPU6000_ADAPTER, 0, mpu6000_cfg);
|
||||
#elif defined(PIOS_I2C_MPU6000_ADAPTER)
|
||||
PIOS_MPU6000_Init(PIOS_I2C_MPU6000_ADAPTER, 0, mpu6000_cfg);
|
||||
#else
|
||||
#error PIOS_INCLUDE_MPU6000 requires one of PIOS_SPI_MPU6000_ADAPTER or PIOS_I2C_MPU6000_ADAPTER
|
||||
#endif
|
||||
PIOS_MPU6000_CONFIG_Configure();
|
||||
#ifndef PIOS_EXCLUDE_ADVANCED_FEATURES
|
||||
PIOS_MPU6000_Register();
|
||||
@ -151,10 +161,14 @@ void PIOS_BOARD_Sensors_Configure()
|
||||
|
||||
if (option == AUXMAGSETTINGS_TYPE_FLEXI) {
|
||||
// i2c_external
|
||||
#ifdef PIOS_I2C_EXTERNAL_ADAPTER
|
||||
i2c_id = PIOS_I2C_EXTERNAL_ADAPTER;
|
||||
#endif
|
||||
} else if (option == AUXMAGSETTINGS_TYPE_I2C) {
|
||||
// i2c_internal (or Sparky2/F3 dedicated I2C port)
|
||||
#ifdef PIOS_I2C_FLEXI_ADAPTER
|
||||
i2c_id = PIOS_I2C_FLEXI_ADAPTER;
|
||||
#endif
|
||||
}
|
||||
|
||||
if (i2c_id) {
|
||||
@ -184,6 +198,13 @@ void PIOS_BOARD_Sensors_Configure()
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef PIOS_INCLUDE_BMP280
|
||||
const struct pios_bmp280_cfg *bmp280_cfg = PIOS_BOARD_HW_DEFS_GetBMP280Cfg(pios_board_info_blob.board_rev);
|
||||
if(bmp280_cfg) {
|
||||
PIOS_BMP280_Init(bmp280_cfg, PIOS_I2C_BMP280_INTERNAL_ADAPTER);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef PIOS_INCLUDE_ADC
|
||||
const struct pios_adc_cfg *adc_cfg = PIOS_BOARD_HW_DEFS_GetAdcCfg(pios_board_info_blob.board_rev);
|
||||
if (adc_cfg) {
|
||||
|
@ -35,6 +35,7 @@
|
||||
#include <stdint.h>
|
||||
#include <pios_constants.h>
|
||||
#include <pios_sensors.h>
|
||||
#include <pios_i2c.h>
|
||||
|
||||
/* Global Variables */
|
||||
|
||||
@ -42,6 +43,9 @@ enum pios_mpu6000_dev_magic {
|
||||
PIOS_MPU6000_DEV_MAGIC = 0x9da9b3ed,
|
||||
};
|
||||
|
||||
#define CALLBACK_TASK_STACKSIZE 256
|
||||
|
||||
|
||||
// sensor driver interface
|
||||
bool PIOS_MPU6000_driver_Test(uintptr_t context);
|
||||
void PIOS_MPU6000_driver_Reset(uintptr_t context);
|
||||
@ -58,13 +62,18 @@ const PIOS_SENSORS_Driver PIOS_MPU6000_Driver = {
|
||||
.is_polled = false,
|
||||
};
|
||||
//
|
||||
|
||||
struct pios_mpu6000_io_driver {
|
||||
int32_t (*SetReg)(uint8_t address, uint8_t buffer);
|
||||
int32_t (*GetReg)(uint8_t address);
|
||||
bool (*ReadSensor)(bool *woken);
|
||||
};
|
||||
|
||||
struct mpu6000_dev {
|
||||
uint32_t spi_id;
|
||||
uint32_t port_id;
|
||||
uint32_t slave_num;
|
||||
QueueHandle_t queue;
|
||||
const struct pios_mpu6000_cfg *cfg;
|
||||
struct pios_mpu6000_io_driver *driver;
|
||||
enum pios_mpu6000_range gyro_range;
|
||||
enum pios_mpu6000_accel_range accel_range;
|
||||
enum pios_mpu6000_filter filter;
|
||||
@ -101,6 +110,7 @@ typedef union {
|
||||
static struct mpu6000_dev *dev;
|
||||
volatile bool mpu6000_configured = false;
|
||||
static mpu6000_data_t mpu6000_data;
|
||||
static uint32_t gyro_read_timestamp;
|
||||
static PIOS_SENSORS_3Axis_SensorsWithTemp *queue_data = 0;
|
||||
#define SENSOR_COUNT 2
|
||||
#define SENSOR_DATA_SIZE (sizeof(PIOS_SENSORS_3Axis_SensorsWithTemp) + sizeof(Vector3i16) * SENSOR_COUNT)
|
||||
@ -109,11 +119,27 @@ static PIOS_SENSORS_3Axis_SensorsWithTemp *queue_data = 0;
|
||||
static struct mpu6000_dev *PIOS_MPU6000_alloc(const struct pios_mpu6000_cfg *cfg);
|
||||
static int32_t PIOS_MPU6000_Validate(struct mpu6000_dev *dev);
|
||||
static void PIOS_MPU6000_Config(struct pios_mpu6000_cfg const *cfg);
|
||||
static int32_t PIOS_MPU6000_SetReg(uint8_t address, uint8_t buffer);
|
||||
static int32_t PIOS_MPU6000_GetReg(uint8_t address);
|
||||
static int32_t PIOS_MPU6000_SPI_SetReg(uint8_t address, uint8_t buffer);
|
||||
static int32_t PIOS_MPU6000_SPI_GetReg(uint8_t address);
|
||||
static void PIOS_MPU6000_SetSpeed(const bool fast);
|
||||
static bool PIOS_MPU6000_HandleData(uint32_t gyro_read_timestamp);
|
||||
static bool PIOS_MPU6000_ReadSensor(bool *woken);
|
||||
static bool PIOS_MPU6000_SPI_ReadSensor(bool *woken);
|
||||
struct pios_mpu6000_io_driver spi_io_driver = {
|
||||
.SetReg = PIOS_MPU6000_SPI_SetReg,
|
||||
.GetReg = PIOS_MPU6000_SPI_GetReg,
|
||||
.ReadSensor = PIOS_MPU6000_SPI_ReadSensor,
|
||||
};
|
||||
|
||||
#ifdef PIOS_INCLUDE_I2C
|
||||
static int32_t PIOS_MPU6000_I2C_SetReg(uint8_t address, uint8_t buffer);
|
||||
static int32_t PIOS_MPU6000_I2C_GetReg(uint8_t address);
|
||||
static bool PIOS_MPU6000_I2C_ReadSensor(bool *woken);
|
||||
struct pios_mpu6000_io_driver i2c_io_driver = {
|
||||
.SetReg = PIOS_MPU6000_I2C_SetReg,
|
||||
.GetReg = PIOS_MPU6000_I2C_GetReg,
|
||||
.ReadSensor = PIOS_MPU6000_I2C_ReadSensor,
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_I2C */
|
||||
|
||||
static int32_t PIOS_MPU6000_Test(void);
|
||||
|
||||
@ -133,6 +159,16 @@ static struct mpu6000_dev *PIOS_MPU6000_alloc(const struct pios_mpu6000_cfg *cfg
|
||||
|
||||
mpu6000_dev->magic = PIOS_MPU6000_DEV_MAGIC;
|
||||
|
||||
if (cfg->i2c_addr == 0) {
|
||||
mpu6000_dev->driver = &spi_io_driver;
|
||||
} else {
|
||||
#ifdef PIOS_INCLUDE_I2C
|
||||
mpu6000_dev->driver = &i2c_io_driver;
|
||||
#else
|
||||
PIOS_Assert(0);
|
||||
#endif
|
||||
}
|
||||
|
||||
mpu6000_dev->queue = xQueueCreate(cfg->max_downsample + 1, SENSOR_DATA_SIZE);
|
||||
PIOS_Assert(mpu6000_dev->queue);
|
||||
|
||||
@ -154,7 +190,7 @@ static int32_t PIOS_MPU6000_Validate(struct mpu6000_dev *vdev)
|
||||
if (vdev->magic != PIOS_MPU6000_DEV_MAGIC) {
|
||||
return -2;
|
||||
}
|
||||
if (vdev->spi_id == 0) {
|
||||
if (vdev->port_id == 0) {
|
||||
return -3;
|
||||
}
|
||||
return 0;
|
||||
@ -164,14 +200,14 @@ static int32_t PIOS_MPU6000_Validate(struct mpu6000_dev *vdev)
|
||||
* @brief Initialize the MPU6000 3-axis gyro sensor.
|
||||
* @return 0 for success, -1 for failure
|
||||
*/
|
||||
int32_t PIOS_MPU6000_Init(uint32_t spi_id, uint32_t slave_num, const struct pios_mpu6000_cfg *cfg)
|
||||
int32_t PIOS_MPU6000_Init(uint32_t port_id, uint32_t slave_num, const struct pios_mpu6000_cfg *cfg)
|
||||
{
|
||||
dev = PIOS_MPU6000_alloc(cfg);
|
||||
if (dev == NULL) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
dev->spi_id = spi_id;
|
||||
dev->port_id = port_id;
|
||||
dev->slave_num = slave_num;
|
||||
dev->cfg = cfg;
|
||||
|
||||
@ -194,13 +230,13 @@ static void PIOS_MPU6000_Config(struct pios_mpu6000_cfg const *cfg)
|
||||
PIOS_MPU6000_Test();
|
||||
|
||||
// Reset chip
|
||||
while (PIOS_MPU6000_SetReg(PIOS_MPU6000_PWR_MGMT_REG, PIOS_MPU6000_PWRMGMT_IMU_RST) != 0) {
|
||||
while (dev->driver->SetReg(PIOS_MPU6000_PWR_MGMT_REG, PIOS_MPU6000_PWRMGMT_IMU_RST) != 0) {
|
||||
;
|
||||
}
|
||||
PIOS_DELAY_WaitmS(50);
|
||||
|
||||
// Reset chip and fifo
|
||||
while (PIOS_MPU6000_SetReg(PIOS_MPU6000_USER_CTRL_REG,
|
||||
while (dev->driver->SetReg(PIOS_MPU6000_USER_CTRL_REG,
|
||||
PIOS_MPU6000_USERCTL_GYRO_RST |
|
||||
PIOS_MPU6000_USERCTL_SIG_COND |
|
||||
PIOS_MPU6000_USERCTL_FIFO_RST) != 0) {
|
||||
@ -208,7 +244,7 @@ static void PIOS_MPU6000_Config(struct pios_mpu6000_cfg const *cfg)
|
||||
}
|
||||
|
||||
// Wait for reset to finish
|
||||
while (PIOS_MPU6000_GetReg(PIOS_MPU6000_USER_CTRL_REG) &
|
||||
while (dev->driver->GetReg(PIOS_MPU6000_USER_CTRL_REG) &
|
||||
(PIOS_MPU6000_USERCTL_GYRO_RST |
|
||||
PIOS_MPU6000_USERCTL_SIG_COND |
|
||||
PIOS_MPU6000_USERCTL_FIFO_RST)) {
|
||||
@ -216,45 +252,45 @@ static void PIOS_MPU6000_Config(struct pios_mpu6000_cfg const *cfg)
|
||||
}
|
||||
PIOS_DELAY_WaitmS(10);
|
||||
// Power management configuration
|
||||
while (PIOS_MPU6000_SetReg(PIOS_MPU6000_PWR_MGMT_REG, cfg->Pwr_mgmt_clk) != 0) {
|
||||
while (dev->driver->SetReg(PIOS_MPU6000_PWR_MGMT_REG, cfg->Pwr_mgmt_clk) != 0) {
|
||||
;
|
||||
}
|
||||
|
||||
// Interrupt configuration
|
||||
while (PIOS_MPU6000_SetReg(PIOS_MPU6000_INT_CFG_REG, cfg->interrupt_cfg) != 0) {
|
||||
while (dev->driver->SetReg(PIOS_MPU6000_INT_CFG_REG, cfg->interrupt_cfg) != 0) {
|
||||
;
|
||||
}
|
||||
|
||||
// Interrupt configuration
|
||||
while (PIOS_MPU6000_SetReg(PIOS_MPU6000_INT_EN_REG, cfg->interrupt_en) != 0) {
|
||||
while (dev->driver->SetReg(PIOS_MPU6000_INT_EN_REG, cfg->interrupt_en) != 0) {
|
||||
;
|
||||
}
|
||||
|
||||
// FIFO storage
|
||||
while (PIOS_MPU6000_SetReg(PIOS_MPU6000_FIFO_EN_REG, cfg->Fifo_store) != 0) {
|
||||
while (dev->driver->SetReg(PIOS_MPU6000_FIFO_EN_REG, cfg->Fifo_store) != 0) {
|
||||
;
|
||||
}
|
||||
PIOS_MPU6000_ConfigureRanges(cfg->gyro_range, cfg->accel_range, cfg->filter);
|
||||
// Interrupt configuration
|
||||
while (PIOS_MPU6000_SetReg(PIOS_MPU6000_USER_CTRL_REG, cfg->User_ctl) != 0) {
|
||||
while (dev->driver->SetReg(PIOS_MPU6000_USER_CTRL_REG, cfg->User_ctl) != 0) {
|
||||
;
|
||||
}
|
||||
|
||||
// Interrupt configuration
|
||||
while (PIOS_MPU6000_SetReg(PIOS_MPU6000_PWR_MGMT_REG, cfg->Pwr_mgmt_clk) != 0) {
|
||||
while (dev->driver->SetReg(PIOS_MPU6000_PWR_MGMT_REG, cfg->Pwr_mgmt_clk) != 0) {
|
||||
;
|
||||
}
|
||||
|
||||
// Interrupt configuration
|
||||
while (PIOS_MPU6000_SetReg(PIOS_MPU6000_INT_CFG_REG, cfg->interrupt_cfg) != 0) {
|
||||
while (dev->driver->SetReg(PIOS_MPU6000_INT_CFG_REG, cfg->interrupt_cfg) != 0) {
|
||||
;
|
||||
}
|
||||
|
||||
// Interrupt configuration
|
||||
while (PIOS_MPU6000_SetReg(PIOS_MPU6000_INT_EN_REG, cfg->interrupt_en) != 0) {
|
||||
while (dev->driver->SetReg(PIOS_MPU6000_INT_EN_REG, cfg->interrupt_en) != 0) {
|
||||
;
|
||||
}
|
||||
if ((PIOS_MPU6000_GetReg(PIOS_MPU6000_INT_EN_REG)) != cfg->interrupt_en) {
|
||||
if ((dev->driver->GetReg(PIOS_MPU6000_INT_EN_REG)) != cfg->interrupt_en) {
|
||||
return;
|
||||
}
|
||||
|
||||
@ -274,12 +310,12 @@ int32_t PIOS_MPU6000_ConfigureRanges(
|
||||
}
|
||||
|
||||
// update filter settings
|
||||
while (PIOS_MPU6000_SetReg(PIOS_MPU6000_DLPF_CFG_REG, filterSetting) != 0) {
|
||||
while (dev->driver->SetReg(PIOS_MPU6000_DLPF_CFG_REG, filterSetting) != 0) {
|
||||
;
|
||||
}
|
||||
|
||||
// Sample rate divider, chosen upon digital filtering settings
|
||||
while (PIOS_MPU6000_SetReg(PIOS_MPU6000_SMPLRT_DIV_REG,
|
||||
while (dev->driver->SetReg(PIOS_MPU6000_SMPLRT_DIV_REG,
|
||||
filterSetting == PIOS_MPU6000_LOWPASS_256_HZ ?
|
||||
dev->cfg->Smpl_rate_div_no_dlp : dev->cfg->Smpl_rate_div_dlp) != 0) {
|
||||
;
|
||||
@ -288,13 +324,13 @@ int32_t PIOS_MPU6000_ConfigureRanges(
|
||||
dev->filter = filterSetting;
|
||||
|
||||
// Gyro range
|
||||
while (PIOS_MPU6000_SetReg(PIOS_MPU6000_GYRO_CFG_REG, gyroRange) != 0) {
|
||||
while (dev->driver->SetReg(PIOS_MPU6000_GYRO_CFG_REG, gyroRange) != 0) {
|
||||
;
|
||||
}
|
||||
|
||||
dev->gyro_range = gyroRange;
|
||||
// Set the accel range
|
||||
while (PIOS_MPU6000_SetReg(PIOS_MPU6000_ACCEL_CFG_REG, accelRange) != 0) {
|
||||
while (dev->driver->SetReg(PIOS_MPU6000_ACCEL_CFG_REG, accelRange) != 0) {
|
||||
;
|
||||
}
|
||||
|
||||
@ -311,11 +347,11 @@ static int32_t PIOS_MPU6000_ClaimBus(bool fast_spi)
|
||||
if (PIOS_MPU6000_Validate(dev) != 0) {
|
||||
return -1;
|
||||
}
|
||||
if (PIOS_SPI_ClaimBus(dev->spi_id) != 0) {
|
||||
if (PIOS_SPI_ClaimBus(dev->port_id) != 0) {
|
||||
return -2;
|
||||
}
|
||||
PIOS_MPU6000_SetSpeed(fast_spi);
|
||||
PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 0);
|
||||
PIOS_SPI_RC_PinSet(dev->port_id, dev->slave_num, 0);
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -323,9 +359,9 @@ static int32_t PIOS_MPU6000_ClaimBus(bool fast_spi)
|
||||
static void PIOS_MPU6000_SetSpeed(const bool fast)
|
||||
{
|
||||
if (fast) {
|
||||
PIOS_SPI_SetClockSpeed(dev->spi_id, dev->cfg->fast_prescaler);
|
||||
PIOS_SPI_SetClockSpeed(dev->port_id, dev->cfg->fast_prescaler);
|
||||
} else {
|
||||
PIOS_SPI_SetClockSpeed(dev->spi_id, dev->cfg->std_prescaler);
|
||||
PIOS_SPI_SetClockSpeed(dev->port_id, dev->cfg->std_prescaler);
|
||||
}
|
||||
}
|
||||
|
||||
@ -340,11 +376,11 @@ static int32_t PIOS_MPU6000_ClaimBusISR(bool *woken, bool fast_spi)
|
||||
if (PIOS_MPU6000_Validate(dev) != 0) {
|
||||
return -1;
|
||||
}
|
||||
if (PIOS_SPI_ClaimBusISR(dev->spi_id, woken) != 0) {
|
||||
if (PIOS_SPI_ClaimBusISR(dev->port_id, woken) != 0) {
|
||||
return -2;
|
||||
}
|
||||
PIOS_MPU6000_SetSpeed(fast_spi);
|
||||
PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 0);
|
||||
PIOS_SPI_RC_PinSet(dev->port_id, dev->slave_num, 0);
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -357,8 +393,8 @@ static int32_t PIOS_MPU6000_ReleaseBus()
|
||||
if (PIOS_MPU6000_Validate(dev) != 0) {
|
||||
return -1;
|
||||
}
|
||||
PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 1);
|
||||
return PIOS_SPI_ReleaseBus(dev->spi_id);
|
||||
PIOS_SPI_RC_PinSet(dev->port_id, dev->slave_num, 1);
|
||||
return PIOS_SPI_ReleaseBus(dev->port_id);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -372,8 +408,8 @@ static int32_t PIOS_MPU6000_ReleaseBusISR(bool *woken)
|
||||
if (PIOS_MPU6000_Validate(dev) != 0) {
|
||||
return -1;
|
||||
}
|
||||
PIOS_SPI_RC_PinSet(dev->spi_id, dev->slave_num, 1);
|
||||
return PIOS_SPI_ReleaseBusISR(dev->spi_id, woken);
|
||||
PIOS_SPI_RC_PinSet(dev->port_id, dev->slave_num, 1);
|
||||
return PIOS_SPI_ReleaseBusISR(dev->port_id, woken);
|
||||
}
|
||||
|
||||
/**
|
||||
@ -381,7 +417,7 @@ static int32_t PIOS_MPU6000_ReleaseBusISR(bool *woken)
|
||||
* @returns The register value or -1 if failure to get bus
|
||||
* @param reg[in] Register address to be read
|
||||
*/
|
||||
static int32_t PIOS_MPU6000_GetReg(uint8_t reg)
|
||||
static int32_t PIOS_MPU6000_SPI_GetReg(uint8_t reg)
|
||||
{
|
||||
uint8_t data;
|
||||
|
||||
@ -389,8 +425,8 @@ static int32_t PIOS_MPU6000_GetReg(uint8_t reg)
|
||||
return -1;
|
||||
}
|
||||
|
||||
PIOS_SPI_TransferByte(dev->spi_id, (0x80 | reg)); // request byte
|
||||
data = PIOS_SPI_TransferByte(dev->spi_id, 0); // receive response
|
||||
PIOS_SPI_TransferByte(dev->port_id, (0x80 | reg)); // request byte
|
||||
data = PIOS_SPI_TransferByte(dev->port_id, 0); // receive response
|
||||
|
||||
PIOS_MPU6000_ReleaseBus();
|
||||
return data;
|
||||
@ -404,18 +440,18 @@ static int32_t PIOS_MPU6000_GetReg(uint8_t reg)
|
||||
* \return -1 if unable to claim SPI bus
|
||||
* \return -2 if unable to claim i2c device
|
||||
*/
|
||||
static int32_t PIOS_MPU6000_SetReg(uint8_t reg, uint8_t data)
|
||||
static int32_t PIOS_MPU6000_SPI_SetReg(uint8_t reg, uint8_t data)
|
||||
{
|
||||
if (PIOS_MPU6000_ClaimBus(false) != 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (PIOS_SPI_TransferByte(dev->spi_id, 0x7f & reg) != 0) {
|
||||
if (PIOS_SPI_TransferByte(dev->port_id, 0x7f & reg) != 0) {
|
||||
PIOS_MPU6000_ReleaseBus();
|
||||
return -2;
|
||||
}
|
||||
|
||||
if (PIOS_SPI_TransferByte(dev->spi_id, data) != 0) {
|
||||
if (PIOS_SPI_TransferByte(dev->port_id, data) != 0) {
|
||||
PIOS_MPU6000_ReleaseBus();
|
||||
return -3;
|
||||
}
|
||||
@ -439,7 +475,7 @@ int32_t PIOS_MPU6000_DummyReadGyros()
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (PIOS_SPI_TransferBlock(dev->spi_id, &buf[0], &rec[0], sizeof(buf), NULL) < 0) {
|
||||
if (PIOS_SPI_TransferBlock(dev->port_id, &buf[0], &rec[0], sizeof(buf), NULL) < 0) {
|
||||
return -2;
|
||||
}
|
||||
|
||||
@ -448,13 +484,111 @@ int32_t PIOS_MPU6000_DummyReadGyros()
|
||||
return 0;
|
||||
}
|
||||
|
||||
#ifdef PIOS_INCLUDE_I2C
|
||||
static int32_t PIOS_MPU6000_I2C_SetReg(uint8_t address, uint8_t buffer)
|
||||
{
|
||||
uint8_t data[] = {
|
||||
address,
|
||||
buffer,
|
||||
};
|
||||
|
||||
const struct pios_i2c_txn txn_list[] = {
|
||||
{
|
||||
.info = __func__,
|
||||
.addr = dev->cfg->i2c_addr,
|
||||
.rw = PIOS_I2C_TXN_WRITE,
|
||||
.len = sizeof(data),
|
||||
.buf = data,
|
||||
}
|
||||
,
|
||||
};
|
||||
|
||||
return PIOS_I2C_Transfer(dev->port_id, txn_list, NELEMENTS(txn_list));
|
||||
}
|
||||
|
||||
static int32_t PIOS_MPU6000_I2C_Read(uint8_t address, uint8_t *buffer, uint8_t len)
|
||||
{
|
||||
uint8_t addr_buffer[] = {
|
||||
address,
|
||||
};
|
||||
|
||||
const struct pios_i2c_txn txn_list[] = {
|
||||
{
|
||||
.info = __func__,
|
||||
.addr = dev->cfg->i2c_addr,
|
||||
.rw = PIOS_I2C_TXN_WRITE,
|
||||
.len = sizeof(addr_buffer),
|
||||
.buf = addr_buffer,
|
||||
}
|
||||
,
|
||||
{
|
||||
.info = __func__,
|
||||
.addr = dev->cfg->i2c_addr,
|
||||
.rw = PIOS_I2C_TXN_READ,
|
||||
.len = len,
|
||||
.buf = buffer,
|
||||
}
|
||||
};
|
||||
|
||||
return PIOS_I2C_Transfer(dev->port_id, txn_list, NELEMENTS(txn_list));
|
||||
}
|
||||
|
||||
static int32_t PIOS_MPU6000_I2C_GetReg(uint8_t address)
|
||||
{
|
||||
uint8_t data;
|
||||
|
||||
if (PIOS_MPU6000_I2C_Read(address, &data, sizeof(data)) < 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
return data;
|
||||
}
|
||||
|
||||
static bool PIOS_MPU6000_I2C_Read_Completed()
|
||||
{
|
||||
return PIOS_MPU6000_HandleData(gyro_read_timestamp);
|
||||
}
|
||||
|
||||
static bool PIOS_MPU6000_I2C_ReadSensor(bool *woken)
|
||||
{
|
||||
static uint8_t addr_buffer[] = {
|
||||
PIOS_MPU6000_SENSOR_FIRST_REG,
|
||||
};
|
||||
|
||||
static struct pios_i2c_txn txn_list[] = {
|
||||
{
|
||||
.info = __func__,
|
||||
// .addr = dev->cfg->i2c_addr,
|
||||
.rw = PIOS_I2C_TXN_WRITE,
|
||||
.len = sizeof(addr_buffer),
|
||||
.buf = addr_buffer,
|
||||
}
|
||||
,
|
||||
{
|
||||
.info = __func__,
|
||||
// .addr = dev->cfg->i2c_addr,
|
||||
.rw = PIOS_I2C_TXN_READ,
|
||||
.len = sizeof(mpu6000_data_t) - 1,
|
||||
.buf = &mpu6000_data.buffer[1],
|
||||
}
|
||||
};
|
||||
|
||||
txn_list[0].addr = dev->cfg->i2c_addr;
|
||||
txn_list[1].addr = dev->cfg->i2c_addr;
|
||||
|
||||
PIOS_I2C_Transfer_CallbackFromISR(dev->port_id, txn_list, NELEMENTS(txn_list), PIOS_MPU6000_I2C_Read_Completed, woken);
|
||||
|
||||
return false; /* we did not read anything now */
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_I2C */
|
||||
|
||||
/*
|
||||
* @brief Read the identification bytes from the MPU6000 sensor
|
||||
* \return ID read from MPU6000 or -1 if failure
|
||||
*/
|
||||
int32_t PIOS_MPU6000_ReadID()
|
||||
{
|
||||
int32_t mpu6000_id = PIOS_MPU6000_GetReg(PIOS_MPU6000_WHOAMI);
|
||||
int32_t mpu6000_id = dev->driver->GetReg(PIOS_MPU6000_WHOAMI);
|
||||
|
||||
if (mpu6000_id < 0) {
|
||||
return -1;
|
||||
@ -541,21 +675,21 @@ static int32_t PIOS_MPU6000_Test(void)
|
||||
|
||||
bool PIOS_MPU6000_IRQHandler(void)
|
||||
{
|
||||
uint32_t gyro_read_timestamp = PIOS_DELAY_GetRaw();
|
||||
gyro_read_timestamp = PIOS_DELAY_GetRaw();
|
||||
bool woken = false;
|
||||
|
||||
if (!mpu6000_configured) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (PIOS_MPU6000_ReadSensor(&woken)) {
|
||||
if (dev->driver->ReadSensor(&woken)) {
|
||||
woken |= PIOS_MPU6000_HandleData(gyro_read_timestamp);
|
||||
}
|
||||
|
||||
return woken;
|
||||
}
|
||||
|
||||
static bool PIOS_MPU6000_HandleData(uint32_t gyro_read_timestamp)
|
||||
static bool PIOS_MPU6000_HandleData(uint32_t gyro_read_timestamp_p)
|
||||
{
|
||||
if (!queue_data) {
|
||||
return false;
|
||||
@ -598,21 +732,22 @@ static bool PIOS_MPU6000_HandleData(uint32_t gyro_read_timestamp)
|
||||
const int16_t temp = GET_SENSOR_DATA(mpu6000_data, Temperature);
|
||||
// Temperature in degrees C = (TEMP_OUT Register Value as a signed quantity)/340 + 36.53
|
||||
queue_data->temperature = 3653 + (temp * 100) / 340;
|
||||
queue_data->timestamp = gyro_read_timestamp;
|
||||
queue_data->timestamp = gyro_read_timestamp_p;
|
||||
|
||||
|
||||
BaseType_t higherPriorityTaskWoken;
|
||||
xQueueSendToBackFromISR(dev->queue, (void *)queue_data, &higherPriorityTaskWoken);
|
||||
return higherPriorityTaskWoken == pdTRUE;
|
||||
}
|
||||
|
||||
static bool PIOS_MPU6000_ReadSensor(bool *woken)
|
||||
static bool PIOS_MPU6000_SPI_ReadSensor(bool *woken)
|
||||
{
|
||||
const uint8_t mpu6000_send_buf[1 + PIOS_MPU6000_SAMPLES_BYTES] = { PIOS_MPU6000_SENSOR_FIRST_REG | 0x80 };
|
||||
|
||||
if (PIOS_MPU6000_ClaimBusISR(woken, true) != 0) {
|
||||
return false;
|
||||
}
|
||||
if (PIOS_SPI_TransferBlock(dev->spi_id, &mpu6000_send_buf[0], &mpu6000_data.buffer[0], sizeof(mpu6000_data_t), NULL) < 0) {
|
||||
if (PIOS_SPI_TransferBlock(dev->port_id, &mpu6000_send_buf[0], &mpu6000_data.buffer[0], sizeof(mpu6000_data_t), NULL) < 0) {
|
||||
PIOS_MPU6000_ReleaseBusISR(woken);
|
||||
return false;
|
||||
}
|
||||
@ -628,7 +763,7 @@ bool PIOS_MPU6000_driver_Test(__attribute__((unused)) uintptr_t context)
|
||||
|
||||
void PIOS_MPU6000_driver_Reset(__attribute__((unused)) uintptr_t context)
|
||||
{
|
||||
PIOS_MPU6000_DummyReadGyros();
|
||||
// PIOS_MPU6000_DummyReadGyros();
|
||||
}
|
||||
|
||||
void PIOS_MPU6000_driver_get_scale(float *scales, uint8_t size, __attribute__((unused)) uintptr_t contet)
|
||||
|
@ -129,6 +129,7 @@ static volatile bool mag_ready = false;
|
||||
static struct mpu9250_dev *dev;
|
||||
volatile bool mpu9250_configured = false;
|
||||
static mpu9250_data_t mpu9250_data;
|
||||
static int32_t mpu9250_id;
|
||||
|
||||
// ! Private functions
|
||||
static struct mpu9250_dev *PIOS_MPU9250_alloc(const struct pios_mpu9250_cfg *cfg);
|
||||
@ -186,7 +187,9 @@ void PIOS_MPU9250_MainRegister()
|
||||
|
||||
void PIOS_MPU9250_MagRegister()
|
||||
{
|
||||
PIOS_SENSORS_Register(&PIOS_MPU9250_Mag_Driver, PIOS_SENSORS_TYPE_3AXIS_MAG, 0);
|
||||
if (mpu9250_id == PIOS_MPU9250_GYRO_ACC_ID) {
|
||||
PIOS_SENSORS_Register(&PIOS_MPU9250_Mag_Driver, PIOS_SENSORS_TYPE_3AXIS_MAG, 0);
|
||||
}
|
||||
}
|
||||
/**
|
||||
* @brief Allocate a new device
|
||||
@ -320,7 +323,9 @@ static void PIOS_MPU9250_Config(struct pios_mpu9250_cfg const *cfg)
|
||||
}
|
||||
|
||||
#ifdef PIOS_MPU9250_MAG
|
||||
PIOS_MPU9250_Mag_Init();
|
||||
if (mpu9250_id == PIOS_MPU9250_GYRO_ACC_ID) {
|
||||
PIOS_MPU9250_Mag_Init();
|
||||
}
|
||||
#endif
|
||||
|
||||
// Interrupt enable
|
||||
@ -514,12 +519,12 @@ static int32_t PIOS_MPU9250_SetReg(uint8_t reg, uint8_t data)
|
||||
*/
|
||||
int32_t PIOS_MPU9250_ReadID()
|
||||
{
|
||||
int32_t mpu9250_id = PIOS_MPU9250_GetReg(PIOS_MPU9250_WHOAMI);
|
||||
int32_t id = PIOS_MPU9250_GetReg(PIOS_MPU9250_WHOAMI);
|
||||
|
||||
if (mpu9250_id < 0) {
|
||||
if (id < 0) {
|
||||
return -1;
|
||||
}
|
||||
return mpu9250_id;
|
||||
return id;
|
||||
}
|
||||
|
||||
static float PIOS_MPU9250_GetScale()
|
||||
@ -566,13 +571,13 @@ static float PIOS_MPU9250_GetAccelScale()
|
||||
static int32_t PIOS_MPU9250_Test(void)
|
||||
{
|
||||
/* Verify that ID matches */
|
||||
int32_t mpu9250_id = PIOS_MPU9250_ReadID();
|
||||
mpu9250_id = PIOS_MPU9250_ReadID();
|
||||
|
||||
if (mpu9250_id < 0) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (mpu9250_id != PIOS_MPU9250_GYRO_ACC_ID) {
|
||||
if ((mpu9250_id != PIOS_MPU9250_GYRO_ACC_ID) && (mpu9250_id != PIOS_MPU6500_GYRO_ACC_ID)) {
|
||||
return -2;
|
||||
}
|
||||
|
||||
|
@ -81,9 +81,8 @@ struct pios_sbus_state {
|
||||
#define SBUS_FL_WEIGHTED_AVE 26
|
||||
|
||||
struct pios_sbus_dev {
|
||||
enum pios_sbus_dev_magic magic;
|
||||
const struct pios_sbus_cfg *cfg;
|
||||
struct pios_sbus_state state;
|
||||
enum pios_sbus_dev_magic magic;
|
||||
struct pios_sbus_state state;
|
||||
};
|
||||
|
||||
/* Allocate S.Bus device descriptor */
|
||||
@ -153,7 +152,6 @@ int32_t PIOS_SBus_Init(uint32_t *sbus_id,
|
||||
uint32_t lower_id)
|
||||
{
|
||||
PIOS_DEBUG_Assert(sbus_id);
|
||||
PIOS_DEBUG_Assert(cfg);
|
||||
PIOS_DEBUG_Assert(driver);
|
||||
|
||||
struct pios_sbus_dev *sbus_dev;
|
||||
@ -163,9 +161,6 @@ int32_t PIOS_SBus_Init(uint32_t *sbus_id,
|
||||
goto out_fail;
|
||||
}
|
||||
|
||||
/* Bind the configuration to the device instance */
|
||||
sbus_dev->cfg = cfg;
|
||||
|
||||
PIOS_SBus_ResetState(&(sbus_dev->state));
|
||||
|
||||
*sbus_id = (uint32_t)sbus_dev;
|
||||
|
@ -100,7 +100,7 @@ extern void PIOS_Servo_Disable()
|
||||
|
||||
GPIO_InitTypeDef init = chan->pin.init;
|
||||
|
||||
#if defined(STM32F40_41xxx) || defined(STM32F446xx) || defined(STM32F411xE)
|
||||
#if defined(STM32F40_41xxx) || defined(STM32F446xx) || defined(STM32F411xE) || defined(STM32F3)
|
||||
init.GPIO_Mode = GPIO_Mode_OUT;
|
||||
#elif defined(STM32F10X_MD)
|
||||
init.GPIO_Mode = GPIO_Mode_Out_PP;
|
||||
@ -147,7 +147,7 @@ static void PIOS_Servo_SetupBank(uint8_t bank_nr)
|
||||
switch (bank->mode) {
|
||||
case PIOS_SERVO_BANK_MODE_PWM:
|
||||
case PIOS_SERVO_BANK_MODE_SINGLE_PULSE:
|
||||
#if defined(STM32F40_41xxx) || defined(STM32F446xx) || defined(STM32F411xE)
|
||||
#if defined(STM32F40_41xxx) || defined(STM32F446xx) || defined(STM32F411xE) || defined(STM32F3)
|
||||
GPIO_PinAFConfig(chan->pin.gpio, chan->pin.pin_source, chan->remap);
|
||||
#elif defined(STM32F10X_MD)
|
||||
init.GPIO_Mode = GPIO_Mode_AF_PP;
|
||||
@ -162,28 +162,27 @@ static void PIOS_Servo_SetupBank(uint8_t bank_nr)
|
||||
/* Set up for output compare function */
|
||||
switch (chan->timer_chan) {
|
||||
case TIM_Channel_1:
|
||||
TIM_OC1Init(chan->timer, &servo_cfg->tim_oc_init);
|
||||
TIM_OC1Init(chan->timer, (TIM_OCInitTypeDef *)&servo_cfg->tim_oc_init);
|
||||
TIM_OC1PreloadConfig(chan->timer, TIM_OCPreload_Enable);
|
||||
break;
|
||||
case TIM_Channel_2:
|
||||
TIM_OC2Init(chan->timer, &servo_cfg->tim_oc_init);
|
||||
TIM_OC2Init(chan->timer, (TIM_OCInitTypeDef *)&servo_cfg->tim_oc_init);
|
||||
TIM_OC2PreloadConfig(chan->timer, TIM_OCPreload_Enable);
|
||||
break;
|
||||
case TIM_Channel_3:
|
||||
TIM_OC3Init(chan->timer, &servo_cfg->tim_oc_init);
|
||||
TIM_OC3Init(chan->timer, (TIM_OCInitTypeDef *)&servo_cfg->tim_oc_init);
|
||||
TIM_OC3PreloadConfig(chan->timer, TIM_OCPreload_Enable);
|
||||
break;
|
||||
case TIM_Channel_4:
|
||||
TIM_OC4Init(chan->timer, &servo_cfg->tim_oc_init);
|
||||
TIM_OC4Init(chan->timer, (TIM_OCInitTypeDef *)&servo_cfg->tim_oc_init);
|
||||
TIM_OC4PreloadConfig(chan->timer, TIM_OCPreload_Enable);
|
||||
break;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case PIOS_SERVO_BANK_MODE_DSHOT:
|
||||
{
|
||||
#if defined(STM32F40_41xxx) || defined(STM32F446xx) || defined(STM32F411xE)
|
||||
#if defined(STM32F40_41xxx) || defined(STM32F446xx) || defined(STM32F411xE) || defined(STM32F3)
|
||||
init.GPIO_Mode = GPIO_Mode_OUT;
|
||||
#elif defined(STM32F10X_MD)
|
||||
init.GPIO_Mode = GPIO_Mode_Out_PP;
|
||||
@ -504,8 +503,8 @@ void PIOS_Servo_SetHz(const uint16_t *speeds, const uint32_t *clock, uint8_t ban
|
||||
|
||||
// Choose the correct prescaler value for the APB the timer is attached
|
||||
|
||||
#if defined(STM32F10X_MD)
|
||||
// F1 has both timer clock domains running at master clock speed
|
||||
#if defined(STM32F10X_MD) || defined(STM32F3)
|
||||
// F1 & F3 have both timer clock domains running at master clock speed
|
||||
timer_clock = PIOS_MASTER_CLOCK;
|
||||
#elif defined(STM32F40_41xxx) || defined(STM32F446xx) || defined(STM32F411xE)
|
||||
if (timer == TIM1 || timer == TIM8 || timer == TIM9 || timer == TIM10 || timer == TIM11) {
|
||||
|
@ -68,4 +68,7 @@ const struct pios_l3gd20_cfg *PIOS_BOARD_HW_DEFS_GetL3GD20Cfg(uint32_t board_rev
|
||||
#ifdef PIOS_INCLUDE_BMA180
|
||||
const struct pios_bma180_cfg *PIOS_BOARD_HW_DEFS_GetBMA180Cfg(uint32_t board_revision);
|
||||
#endif
|
||||
#ifdef PIOS_INCLUDE_BMP280
|
||||
const struct pios_bmp280_cfg *PIOS_BOARD_HW_DEFS_GetBMP280Cfg(uint32_t board_revision);
|
||||
#endif
|
||||
#endif /* PIOS_BOARD_HW_H */
|
||||
|
@ -62,13 +62,6 @@ enum PIOS_COM_Parity {
|
||||
PIOS_COM_Parity_Odd,
|
||||
};
|
||||
|
||||
enum PIOS_COM_Mode {
|
||||
PIOS_COM_Mode_Unchanged = 0,
|
||||
PIOS_COM_Mode_Rx = (1 << 0),
|
||||
PIOS_COM_Mode_Tx = (1 << 1),
|
||||
PIOS_COM_Mode_RxTx = (PIOS_COM_Mode_Rx | PIOS_COM_Mode_Tx),
|
||||
};
|
||||
|
||||
struct pios_com_driver {
|
||||
void (*set_baud)(uint32_t id, uint32_t baud);
|
||||
void (*set_config)(uint32_t usart_id, enum PIOS_COM_Word_Length word_len, enum PIOS_COM_Parity parity, enum PIOS_COM_StopBits stop_bits, uint32_t baud_rate);
|
||||
|
@ -72,6 +72,15 @@ const struct pios_flash_jedec_cfg pios_flash_jedec_catalog[] =
|
||||
.fast_read = 0x0B,
|
||||
.fast_read_dummy_bytes = 1,
|
||||
},
|
||||
{ // 25q64
|
||||
.expect_manufacturer = JEDEC_MANUFACTURER_WINBOND,
|
||||
.expect_memorytype = 0x40,
|
||||
.expect_capacity = 0x17,
|
||||
.sector_erase = 0x20,
|
||||
.chip_erase = 0x60,
|
||||
.fast_read = 0x0B,
|
||||
.fast_read_dummy_bytes = 1,
|
||||
},
|
||||
{ // 25q512
|
||||
.expect_manufacturer = JEDEC_MANUFACTURER_MICRON,
|
||||
.expect_memorytype = 0xBA,
|
||||
|
@ -73,9 +73,13 @@ enum pios_i2c_error_count {
|
||||
PIOS_I2C_ERROR_COUNT_NUMELEM,
|
||||
};
|
||||
|
||||
typedef bool (*pios_i2c_callback)();
|
||||
|
||||
/* Public Functions */
|
||||
extern int32_t PIOS_I2C_Transfer(uint32_t i2c_id, const struct pios_i2c_txn txn_list[], uint32_t num_txns);
|
||||
extern int32_t PIOS_I2C_Transfer_Callback(uint32_t i2c_id, const struct pios_i2c_txn txn_list[], uint32_t num_txns, void *callback);
|
||||
extern int32_t PIOS_I2C_Transfer_Callback(uint32_t i2c_id, const struct pios_i2c_txn txn_list[], uint32_t num_txns, pios_i2c_callback callback);
|
||||
extern int32_t PIOS_I2C_Transfer_CallbackFromISR(uint32_t i2c_id, const struct pios_i2c_txn txn_list[], uint32_t num_txns, pios_i2c_callback callback, bool *woken);
|
||||
|
||||
extern void PIOS_I2C_EV_IRQ_Handler(uint32_t i2c_id);
|
||||
extern void PIOS_I2C_ER_IRQ_Handler(uint32_t i2c_id);
|
||||
extern void PIOS_I2C_IRQ_Handler(uint32_t i2c_id);
|
||||
|
@ -69,7 +69,7 @@ struct pios_i2c_adapter {
|
||||
const struct pios_i2c_txn *active_txn;
|
||||
const struct pios_i2c_txn *last_txn;
|
||||
|
||||
void (*callback)();
|
||||
pios_i2c_callback callback;
|
||||
|
||||
uint8_t *active_byte;
|
||||
uint8_t *last_byte;
|
||||
|
@ -134,6 +134,7 @@ enum pios_mpu6000_orientation { // clockwise rotation from board forward
|
||||
|
||||
struct pios_mpu6000_cfg {
|
||||
const struct pios_exti_cfg *exti_cfg; /* Pointer to the EXTI configuration */
|
||||
uint8_t i2c_addr;
|
||||
|
||||
uint8_t Fifo_store; /* FIFO storage of different readings (See datasheet page 31 for more details) */
|
||||
|
||||
@ -154,7 +155,7 @@ struct pios_mpu6000_cfg {
|
||||
};
|
||||
|
||||
/* Public Functions */
|
||||
extern int32_t PIOS_MPU6000_Init(uint32_t spi_id, uint32_t slave_num, const struct pios_mpu6000_cfg *new_cfg);
|
||||
extern int32_t PIOS_MPU6000_Init(uint32_t port_id, uint32_t slave_num, const struct pios_mpu6000_cfg *new_cfg);
|
||||
extern int32_t PIOS_MPU6000_ConfigureRanges(enum pios_mpu6000_range gyroRange, enum pios_mpu6000_accel_range accelRange, enum pios_mpu6000_filter filterSetting);
|
||||
extern int32_t PIOS_MPU6000_ReadID();
|
||||
extern void PIOS_MPU6000_Register();
|
||||
|
@ -153,6 +153,7 @@
|
||||
#define PIOS_MPU9250_ASAZ 0X12
|
||||
|
||||
/* IDs */
|
||||
#define PIOS_MPU6500_GYRO_ACC_ID 0x70
|
||||
#define PIOS_MPU9250_GYRO_ACC_ID 0x71
|
||||
#define PIOS_MPU9250_MAG_ID 0x48
|
||||
|
||||
|
@ -85,11 +85,6 @@
|
||||
*/
|
||||
struct pios_sbus_cfg {
|
||||
bool non_inverted;
|
||||
// struct stm32_gpio inv;
|
||||
// void (*gpio_clk_func)(uint32_t periph, FunctionalState state);
|
||||
// uint32_t gpio_clk_periph;
|
||||
// BitAction gpio_inv_enable;
|
||||
// BitAction gpio_inv_disable;
|
||||
};
|
||||
|
||||
extern const struct pios_rcvr_driver pios_sbus_rcvr_driver;
|
||||
|
@ -64,6 +64,8 @@ extern "C" {
|
||||
#include <stm32f4xx_rcc.h>
|
||||
#elif defined(STM32F0)
|
||||
#include <stm32f0xx.h>
|
||||
#elif defined(STM32F3)
|
||||
#include <stm32f30x.h>
|
||||
#else
|
||||
#error "No Architecture defined"
|
||||
#endif
|
||||
|
@ -289,8 +289,6 @@ static void PIOS_USART_ChangeBaud(uint32_t usart_id, uint32_t baud)
|
||||
* \param[in] word_len Requested word length
|
||||
* \param[in] stop_bits Requested stop bits
|
||||
* \param[in] parity Requested parity
|
||||
* \param[in] baud_rate Requested baud rate
|
||||
* \param[in] mode Requested mode
|
||||
*
|
||||
*/
|
||||
static void PIOS_USART_ChangeConfig(uint32_t usart_id,
|
||||
|
@ -9,7 +9,7 @@ PIOS_DEVLIB := $(dir $(lastword $(MAKEFILE_LIST)))
|
||||
LINKER_SCRIPTS_PATH = $(PIOS_DEVLIB)
|
||||
|
||||
# Compiler options implied by the F10x
|
||||
CDEFS += -DSTM32F10X -DSTM32F10X_$(MODEL)
|
||||
CDEFS += -DSTM32F10X -DSTM32F10X_$(MODEL) -DSTM32F1
|
||||
CDEFS += -DUSE_STDPERIPH_DRIVER
|
||||
CDEFS += -DARM_MATH_CM3
|
||||
CDEFS += -DHSE_VALUE=$(OSCILLATOR_FREQ)
|
||||
|
@ -86,6 +86,9 @@ void PIOS_USB_HID_RegisterHidReport(const uint8_t *desc, uint16_t desc_size)
|
||||
Hid_Report_Descriptor.Descriptor_Size = desc_size;
|
||||
}
|
||||
|
||||
void PIOS_USBHOOK_Deactivate(void)
|
||||
{}
|
||||
|
||||
#include "stm32f10x.h" /* __IO */
|
||||
__IO uint8_t EXTI_Enable;
|
||||
|
||||
|
39
flight/pios/stm32f30x/inc/pios_architecture.h
Normal file
39
flight/pios/stm32f30x/inc/pios_architecture.h
Normal file
@ -0,0 +1,39 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pios_architecture.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2013.
|
||||
* @brief Architecture specific macros and definitions
|
||||
* --
|
||||
* @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
|
||||
*/
|
||||
|
||||
#ifndef PIOS_ARCHITECTURE_H
|
||||
#define PIOS_ARCHITECTURE_H
|
||||
|
||||
// defines for adc
|
||||
#define PIOS_ADC_VOLTAGE_SCALE 3.30f / 4096.0f
|
||||
|
||||
// defines for Temp measurements
|
||||
#define PIOS_ADC_STM32_TEMP_V25 0.76f /* V */
|
||||
#define PIOS_ADC_STM32_TEMP_AVG_SLOPE 2.5f /* mV/C */
|
||||
#define PIOS_CONVERT_VOLT_TO_CPU_TEMP(x) ((x - PIOS_ADC_STM32_TEMP_V25) * 1000.0f / PIOS_ADC_STM32_TEMP_AVG_SLOPE + 25.0f)
|
||||
|
||||
|
||||
#endif /* PIOS_ARCHITECTURE_H */
|
43
flight/pios/stm32f30x/inc/pios_delay_raw.h
Normal file
43
flight/pios/stm32f30x/inc/pios_delay_raw.h
Normal file
@ -0,0 +1,43 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_DELAY Delay Functions
|
||||
* @brief PiOS Delay functionality
|
||||
* @{
|
||||
*
|
||||
* @file pios_delay_raw.h
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016-2017.
|
||||
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Settings functions 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
|
||||
*/
|
||||
#ifndef PIOS_DELAY_RAW_H
|
||||
#define PIOS_DELAY_RAW_H
|
||||
|
||||
/* these should be defined by CMSIS, but they aren't */
|
||||
#define DWT_CTRL (*(volatile uint32_t *)0xe0001000)
|
||||
#define CYCCNTENA (1 << 0)
|
||||
#define DWT_CYCCNT (*(volatile uint32_t *)0xe0001004)
|
||||
|
||||
#define PIOS_DELAY_GetRaw() (DWT_CYCCNT)
|
||||
|
||||
extern uint32_t PIOS_DELAY_GetRawHz();
|
||||
|
||||
#endif /* PIOS_DELAY_RAW_H */
|
52
flight/pios/stm32f30x/inc/pios_servo_config.h
Normal file
52
flight/pios/stm32f30x/inc/pios_servo_config.h
Normal file
@ -0,0 +1,52 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pios_servp_config.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2013.
|
||||
* @brief Architecture specific macros and definitions
|
||||
* --
|
||||
* @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
|
||||
*/
|
||||
#ifndef PIOS_SERVO_CONFIG_H_
|
||||
#define PIOS_SERVO_CONFIG_H_
|
||||
|
||||
|
||||
/**
|
||||
* Generic servo pin configuration structure for an STM32F4xx
|
||||
*/
|
||||
#define TIM_SERVO_CHANNEL_CONFIG(_timer, _channel, _gpio, _pin) \
|
||||
{ \
|
||||
.timer = _timer, \
|
||||
.timer_chan = TIM_Channel_##_channel, \
|
||||
.pin = { \
|
||||
.gpio = GPIO##_gpio, \
|
||||
.init = { \
|
||||
.GPIO_Pin = GPIO_Pin_##_pin, \
|
||||
.GPIO_Speed = GPIO_Speed_2MHz, \
|
||||
.GPIO_Mode = GPIO_Mode_AF, \
|
||||
.GPIO_OType = GPIO_OType_PP, \
|
||||
.GPIO_PuPd = GPIO_PuPd_UP \
|
||||
}, \
|
||||
.pin_source = GPIO_PinSource##_pin, \
|
||||
}, \
|
||||
.remap = GPIO_AF_P##_gpio##_pin##_##_timer, \
|
||||
}
|
||||
|
||||
|
||||
#endif /* PIOS_SERVO_CONFIG_H_ */
|
39
flight/pios/stm32f30x/inc/pios_usart_config.h
Normal file
39
flight/pios/stm32f30x/inc/pios_usart_config.h
Normal file
@ -0,0 +1,39 @@
|
||||
/*
|
||||
* pios_usart_config.h
|
||||
*/
|
||||
|
||||
#ifndef PIOS_USART_CONFIG_H_
|
||||
#define PIOS_USART_CONFIG_H_
|
||||
|
||||
/**
|
||||
* Generic USART configuration structure for an STM32F30x port.
|
||||
*/
|
||||
#define USART_CONFIG(_usart, _rx_gpio, _rx_pin, _tx_gpio, _tx_pin) \
|
||||
{ \
|
||||
.regs = _usart, \
|
||||
.remap = GPIO_AF_##_usart, \
|
||||
.rx = { \
|
||||
.gpio = GPIO##_rx_gpio, \
|
||||
.init = { \
|
||||
.GPIO_Pin = GPIO_Pin_##_rx_pin, \
|
||||
.GPIO_Mode = GPIO_Mode_AF, \
|
||||
.GPIO_Speed = GPIO_Speed_50MHz, \
|
||||
.GPIO_OType = GPIO_OType_PP, \
|
||||
.GPIO_PuPd = GPIO_PuPd_UP, \
|
||||
}, \
|
||||
.pin_source = GPIO_PinSource##_rx_pin, \
|
||||
}, \
|
||||
.tx = { \
|
||||
.gpio = GPIO##_tx_gpio, \
|
||||
.init = { \
|
||||
.GPIO_Pin = GPIO_Pin_##_tx_pin, \
|
||||
.GPIO_Mode = GPIO_Mode_AF, \
|
||||
.GPIO_Speed = GPIO_Speed_50MHz, \
|
||||
.GPIO_OType = GPIO_OType_PP, \
|
||||
.GPIO_PuPd = GPIO_PuPd_UP, \
|
||||
}, \
|
||||
.pin_source = GPIO_PinSource##_tx_pin, \
|
||||
}, \
|
||||
}
|
||||
|
||||
#endif /* PIOS_USART_CONFIG_H_ */
|
82
flight/pios/stm32f30x/inc/stm32f30x_conf.h
Normal file
82
flight/pios/stm32f30x/inc/stm32f30x_conf.h
Normal file
@ -0,0 +1,82 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @file stm32f30x_conf.h
|
||||
* @author MCD Application Team
|
||||
* @version V1.0.0
|
||||
* @date 04-September-2012
|
||||
* @brief Library configuration file.
|
||||
******************************************************************************
|
||||
* @attention
|
||||
*
|
||||
* <h2><center>© 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.
|
||||
* You may obtain a copy of the License at:
|
||||
*
|
||||
* http://www.st.com/software_license_agreement_liberty_v2
|
||||
*
|
||||
* Unless required by applicable law or agreed to in writing, software
|
||||
* distributed under the License is distributed on an "AS IS" BASIS,
|
||||
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||
* See the License for the specific language governing permissions and
|
||||
* limitations under the License.
|
||||
*
|
||||
******************************************************************************
|
||||
*/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef __STM32F30X_CONF_H
|
||||
#define __STM32F30X_CONF_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
/* Comment the line below to disable peripheral header file inclusion */
|
||||
#include "stm32f30x_adc.h"
|
||||
#include "stm32f30x_can.h"
|
||||
#include "stm32f30x_crc.h"
|
||||
#include "stm32f30x_comp.h"
|
||||
#include "stm32f30x_dac.h"
|
||||
#include "stm32f30x_dbgmcu.h"
|
||||
#include "stm32f30x_dma.h"
|
||||
#include "stm32f30x_exti.h"
|
||||
#include "stm32f30x_flash.h"
|
||||
#include "stm32f30x_gpio.h"
|
||||
#include "stm32f30x_syscfg.h"
|
||||
#include "stm32f30x_i2c.h"
|
||||
#include "stm32f30x_iwdg.h"
|
||||
#include "stm32f30x_opamp.h"
|
||||
#include "stm32f30x_pwr.h"
|
||||
#include "stm32f30x_rcc.h"
|
||||
#include "stm32f30x_rtc.h"
|
||||
#include "stm32f30x_spi.h"
|
||||
#include "stm32f30x_tim.h"
|
||||
#include "stm32f30x_usart.h"
|
||||
#include "stm32f30x_wwdg.h"
|
||||
#include "stm32f30x_misc.h" /* High level functions for NVIC and SysTick (add-on to CMSIS functions) */
|
||||
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
/* Uncomment the line below to expanse the "assert_param" macro in the
|
||||
Standard Peripheral Library drivers code */
|
||||
/* #define USE_FULL_ASSERT 1 */
|
||||
|
||||
/* Exported macro ------------------------------------------------------------*/
|
||||
#ifdef USE_FULL_ASSERT
|
||||
|
||||
/**
|
||||
* @brief The assert_param macro is used for function's parameters check.
|
||||
* @param expr: If expr is false, it calls assert_failed function which reports
|
||||
* the name of the source file and the source line number of the call
|
||||
* that failed. If expr is true, it returns no value.
|
||||
* @retval None
|
||||
*/
|
||||
#define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__))
|
||||
/* Exported functions ------------------------------------------------------- */
|
||||
void assert_failed(uint8_t *file, uint32_t line);
|
||||
#else
|
||||
#define assert_param(expr) ((void)0)
|
||||
#endif /* USE_FULL_ASSERT */
|
||||
|
||||
#endif /* __STM32F30X_CONF_H */
|
||||
|
||||
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
197
flight/pios/stm32f30x/inc/usb_conf.h
Normal file
197
flight/pios/stm32f30x/inc/usb_conf.h
Normal file
@ -0,0 +1,197 @@
|
||||
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
|
||||
* File Name : usb_conf.h
|
||||
* Author : MCD Application Team
|
||||
* Version : V3.2.1
|
||||
* Date : 07/05/2010
|
||||
* Description : Custom HID demo configuration file
|
||||
********************************************************************************
|
||||
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
|
||||
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
|
||||
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
|
||||
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
|
||||
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
|
||||
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
|
||||
*******************************************************************************/
|
||||
|
||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||
#ifndef __USB_CONF_H
|
||||
#define __USB_CONF_H
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
/* Exported types ------------------------------------------------------------*/
|
||||
/* Exported constants --------------------------------------------------------*/
|
||||
/* Exported macro ------------------------------------------------------------*/
|
||||
/* Exported functions ------------------------------------------------------- */
|
||||
/* External variables --------------------------------------------------------*/
|
||||
|
||||
#ifndef STM32F10X_CL
|
||||
/*-------------------------------------------------------------*/
|
||||
/* -------------- Buffer Description Table -----------------*/
|
||||
/*-------------------------------------------------------------*/
|
||||
/* buffer table base address */
|
||||
/* buffer table base address */
|
||||
#define BTABLE_ADDRESS (0x00)
|
||||
|
||||
/* EP0 */
|
||||
/* rx/tx buffer base address */
|
||||
#define ENDP0_RXADDR (0x20)
|
||||
#define ENDP0_TXADDR (0x40)
|
||||
|
||||
/* EP1 */
|
||||
/* rx/tx buffer base address */
|
||||
#define ENDP1_TXADDR (0x60)
|
||||
#define ENDP1_RXADDR (0x80)
|
||||
|
||||
/* EP2 */
|
||||
/* rx/tx buffer base address */
|
||||
#define ENDP2_TXADDR (0x100)
|
||||
#define ENDP2_RXADDR (0x140)
|
||||
|
||||
/* EP3 */
|
||||
/* rx/tx buffer base address */
|
||||
#define ENDP3_TXADDR (0x180)
|
||||
#define ENDP3_RXADDR (0x1C0)
|
||||
|
||||
/*-------------------------------------------------------------*/
|
||||
/* ------------------- ISTR events -------------------------*/
|
||||
/*-------------------------------------------------------------*/
|
||||
/* IMR_MSK */
|
||||
/* mask defining which events has to be handled */
|
||||
/* by the device application software */
|
||||
#define IMR_MSK \
|
||||
(CNTR_CTRM | CNTR_WKUPM | CNTR_SUSPM | CNTR_ERRM | CNTR_SOFM \
|
||||
| CNTR_ESOFM | CNTR_RESETM)
|
||||
|
||||
/* Provide a callback function for SOF so we can do early USB detection */
|
||||
#define SOF_CALLBACK
|
||||
|
||||
/* Provide a callback function for SUSPend so we can notice a cable removal event */
|
||||
#define SUSP_CALLBACK
|
||||
|
||||
#endif /* STM32F10X_CL */
|
||||
|
||||
#ifdef STM32F10X_CL
|
||||
|
||||
/*******************************************************************************
|
||||
* FIFO Size Configuration
|
||||
*
|
||||
* (i) Dedicated data FIFO SPRAM of 1.25 Kbytes = 1280 bytes = 320 32-bits words
|
||||
* available for the endpoints IN and OUT.
|
||||
* Device mode features:
|
||||
* -1 bidirectional CTRL EP 0
|
||||
* -3 IN EPs to support any kind of Bulk, Interrupt or Isochronous transfer
|
||||
* -3 OUT EPs to support any kind of Bulk, Interrupt or Isochronous transfer
|
||||
*
|
||||
* ii) Receive data FIFO size = RAM for setup packets +
|
||||
* OUT endpoint control information +
|
||||
* data OUT packets + miscellaneous
|
||||
* Space = ONE 32-bits words
|
||||
* --> RAM for setup packets = 4 * n + 6 space
|
||||
* (n is the nbr of CTRL EPs the device core supports)
|
||||
* --> OUT EP CTRL info = 1 space
|
||||
* (one space for status information written to the FIFO along with each
|
||||
* received packet)
|
||||
* --> data OUT packets = (Largest Packet Size / 4) + 1 spaces
|
||||
* (MINIMUM to receive packets)
|
||||
* --> OR data OUT packets = at least 2*(Largest Packet Size / 4) + 1 spaces
|
||||
* (if high-bandwidth EP is enabled or multiple isochronous EPs)
|
||||
* --> miscellaneous = 1 space per OUT EP
|
||||
* (one space for transfer complete status information also pushed to the
|
||||
* FIFO with each endpoint's last packet)
|
||||
*
|
||||
* (iii)MINIMUM RAM space required for each IN EP Tx FIFO = MAX packet size for
|
||||
* that particular IN EP. More space allocated in the IN EP Tx FIFO results
|
||||
* in a better performance on the USB and can hide latencies on the AHB.
|
||||
*
|
||||
* (iv) TXn min size = 16 words. (n : Transmit FIFO index)
|
||||
* (v) When a TxFIFO is not used, the Configuration should be as follows:
|
||||
* case 1 : n > m and Txn is not used (n,m : Transmit FIFO indexes)
|
||||
* --> Txm can use the space allocated for Txn.
|
||||
* case2 : n < m and Txn is not used (n,m : Transmit FIFO indexes)
|
||||
* --> Txn should be configured with the minimum space of 16 words
|
||||
* (vi) The FIFO is used optimally when used TxFIFOs are allocated in the top
|
||||
* of the FIFO.Ex: use EP1 and EP2 as IN instead of EP1 and EP3 as IN ones.
|
||||
*******************************************************************************/
|
||||
|
||||
#define RX_FIFO_SIZE 128
|
||||
#define TX0_FIFO_SIZE 64
|
||||
#define TX1_FIFO_SIZE 64
|
||||
#define TX2_FIFO_SIZE 16
|
||||
#define TX3_FIFO_SIZE 16
|
||||
|
||||
/* OTGD-FS-DEVICE IP interrupts Enable definitions */
|
||||
/* Uncomment the define to enable the selected interrupt */
|
||||
// #define INTR_MODEMISMATCH
|
||||
#define INTR_SOFINTR
|
||||
#define INTR_RXSTSQLVL /* Mandatory */
|
||||
// #define INTR_NPTXFEMPTY
|
||||
// #define INTR_GINNAKEFF
|
||||
// #define INTR_GOUTNAKEFF
|
||||
// #define INTR_ERLYSUSPEND
|
||||
#define INTR_USBSUSPEND /* Mandatory */
|
||||
#define INTR_USBRESET /* Mandatory */
|
||||
#define INTR_ENUMDONE /* Mandatory */
|
||||
// #define INTR_ISOOUTDROP
|
||||
// #define INTR_EOPFRAME
|
||||
// #define INTR_EPMISMATCH
|
||||
#define INTR_INEPINTR /* Mandatory */
|
||||
#define INTR_OUTEPINTR /* Mandatory */
|
||||
// #define INTR_INCOMPLISOIN
|
||||
// #define INTR_INCOMPLISOOUT
|
||||
#define INTR_WKUPINTR /* Mandatory */
|
||||
|
||||
/* OTGD-FS-DEVICE IP interrupts subroutines */
|
||||
/* Comment the define to enable the selected interrupt subroutine and replace it
|
||||
by user code */
|
||||
#define INTR_MODEMISMATCH_Callback NOP_Process
|
||||
#define INTR_SOFINTR_Callback NOP_Process
|
||||
#define INTR_RXSTSQLVL_Callback NOP_Process
|
||||
#define INTR_NPTXFEMPTY_Callback NOP_Process
|
||||
#define INTR_NPTXFEMPTY_Callback NOP_Process
|
||||
#define INTR_GINNAKEFF_Callback NOP_Process
|
||||
#define INTR_GOUTNAKEFF_Callback NOP_Process
|
||||
#define INTR_ERLYSUSPEND_Callback NOP_Process
|
||||
#define INTR_USBSUSPEND_Callback NOP_Process
|
||||
#define INTR_USBRESET_Callback NOP_Process
|
||||
#define INTR_ENUMDONE_Callback NOP_Process
|
||||
#define INTR_ISOOUTDROP_Callback NOP_Process
|
||||
#define INTR_EOPFRAME_Callback NOP_Process
|
||||
#define INTR_EPMISMATCH_Callback NOP_Process
|
||||
#define INTR_INEPINTR_Callback NOP_Process
|
||||
#define INTR_OUTEPINTR_Callback NOP_Process
|
||||
#define INTR_INCOMPLISOIN_Callback NOP_Process
|
||||
#define INTR_INCOMPLISOOUT_Callback NOP_Process
|
||||
#define INTR_WKUPINTR_Callback NOP_Process
|
||||
|
||||
/* Isochronous data update */
|
||||
#define INTR_RXSTSQLVL_ISODU_Callback NOP_Process
|
||||
|
||||
/* Isochronous transfer parameters */
|
||||
/* Size of a single Isochronous buffer (size of a single transfer) */
|
||||
#define ISOC_BUFFER_SZE 1
|
||||
/* Number of sub-buffers (number of single buffers/transfers), should be even */
|
||||
#define NUM_SUB_BUFFERS 2
|
||||
|
||||
#endif /* STM32F10X_CL */
|
||||
|
||||
/* CTR service routines */
|
||||
/* associated to defined endpoints */
|
||||
#define EP1_IN_Callback NOP_Process
|
||||
#define EP2_IN_Callback NOP_Process
|
||||
#define EP3_IN_Callback NOP_Process
|
||||
#define EP4_IN_Callback NOP_Process
|
||||
#define EP5_IN_Callback NOP_Process
|
||||
#define EP6_IN_Callback NOP_Process
|
||||
#define EP7_IN_Callback NOP_Process
|
||||
|
||||
#define EP1_OUT_Callback NOP_Process
|
||||
#define EP2_OUT_Callback NOP_Process
|
||||
#define EP3_OUT_Callback NOP_Process
|
||||
#define EP4_OUT_Callback NOP_Process
|
||||
#define EP5_OUT_Callback NOP_Process
|
||||
#define EP6_OUT_Callback NOP_Process
|
||||
#define EP7_OUT_Callback NOP_Process
|
||||
|
||||
#endif /*__USB_CONF_H*/
|
||||
|
||||
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/
|
69
flight/pios/stm32f30x/library.mk
Normal file
69
flight/pios/stm32f30x/library.mk
Normal file
@ -0,0 +1,69 @@
|
||||
#
|
||||
# Rules to (help) build the F30x device support.
|
||||
#
|
||||
|
||||
# Directory containing this makefile
|
||||
PIOS_DEVLIB := $(dir $(lastword $(MAKEFILE_LIST)))
|
||||
|
||||
USE_USB ?= YES
|
||||
|
||||
# Hardcoded linker script names for now
|
||||
LINKER_SCRIPTS_APP = $(OPSYSTEM)/memory.ld \
|
||||
$(OPSYSTEM)/../common/sections.ld
|
||||
LINKER_SCRIPTS_BL = $(OPSYSTEM)/memory.ld \
|
||||
$(OPSYSTEM)/../common/sections.ld
|
||||
# _compat linker script are aimed at bootloader updater to guarantee to be compatible with earlier bootloaders.
|
||||
LINKER_SCRIPTS_COMPAT = $(PIOS_DEVLIB)link_$(BOARD)_fw_memory.ld \
|
||||
$(PIOS_DEVLIB)link_$(BOARD)_sections_compat.ld
|
||||
|
||||
CDEFS += -D$(CHIP) -DSTM32F3
|
||||
CDEFS += -DHSE_VALUE=$(OSCILLATOR_FREQ)
|
||||
CDEFS += -DUSE_STDPERIPH_DRIVER
|
||||
CDEFS += -DARM_MATH_CM4 -D__FPU_PRESENT=1
|
||||
CDEFS += -DPIOS_TARGET_PROVIDES_FAST_HEAP
|
||||
|
||||
ARCHFLAGS += -mcpu=cortex-m4 -march=armv7e-m -mfpu=fpv4-sp-d16 -mfloat-abi=hard
|
||||
|
||||
# PIOS device library source and includes
|
||||
PIOS_DEVLIB_SRC = $(sort $(wildcard $(PIOS_DEVLIB)*.c))
|
||||
|
||||
ifeq ($(PIOS_OMITS_USB),YES)
|
||||
SRC += $(filter-out $(wildcard $(PIOS_DEVLIB)pios_usb*.c), $(PIOS_DEVLIB_SRC))
|
||||
else
|
||||
SRC += $(PIOS_DEVLIB_SRC)
|
||||
endif
|
||||
|
||||
EXTRAINCDIRS += $(PIOS_DEVLIB)inc
|
||||
|
||||
# CMSIS for the F3
|
||||
include $(PIOSCOMMON)/libraries/CMSIS/library.mk
|
||||
CMSIS_DEVICEDIR := $(PIOS_DEVLIB)libraries/CMSIS3/Device/ST/STM32F30x
|
||||
SRC += $(OPSYSTEM)/../common/system.c
|
||||
EXTRAINCDIRS += $(CMSIS_DEVICEDIR)/Include
|
||||
|
||||
# ST Peripheral library
|
||||
PERIPHLIB = $(PIOS_DEVLIB)libraries/STM32F30x_StdPeriph_Driver
|
||||
ALL_SPL_SOURCES = $(sort $(wildcard $(PERIPHLIB)/src/*.c))
|
||||
SPL_SOURCES = $(filter-out %stm32f30x_can.c, $(ALL_SPL_SOURCES))
|
||||
SRC += $(SPL_SOURCES)
|
||||
EXTRAINCDIRS += $(PERIPHLIB)/inc
|
||||
|
||||
ifneq ($(PIOS_OMITS_USB),YES)
|
||||
# ST USB Device library
|
||||
USBDEVLIB = $(PIOS_DEVLIB)/libraries/STM32_USB-FS-Device_Driver
|
||||
SRC += $(sort $(wildcard $(USBDEVLIB)/src/*.c))
|
||||
EXTRAINCDIRS += $(USBDEVLIB)/inc
|
||||
endif
|
||||
|
||||
#
|
||||
# FreeRTOS
|
||||
#
|
||||
# If the application has included the generic FreeRTOS support, then add in
|
||||
# the device-specific pieces of the code.
|
||||
#
|
||||
ifneq ($(FREERTOS_DIR),)
|
||||
FREERTOS_PORTDIR := $(FREERTOS_DIR)
|
||||
SRC += $(sort $(wildcard $(FREERTOS_PORTDIR)/portable/GCC/ARM_CM4F/*.c))
|
||||
EXTRAINCDIRS += $(FREERTOS_PORTDIR)/portable/GCC/ARM_CM4F
|
||||
include $(PIOSCOMMON)/libraries/msheap/library.mk
|
||||
endif
|
@ -0,0 +1,7 @@
|
||||
MEMORY
|
||||
{
|
||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 0x004000 - 0x000080
|
||||
BD_INFO (r) : ORIGIN = 0x08004000 - 0x80, LENGTH = 0x000080
|
||||
SRAM (rwx) : ORIGIN = 0x20000000, LENGTH = 0x009000
|
||||
CCSRAM (rw) : ORIGIN = 0x10000000, LENGTH = 0x002000
|
||||
}
|
@ -0,0 +1,8 @@
|
||||
MEMORY
|
||||
{
|
||||
BD_INFO (r) : ORIGIN = 0x08004000 - 0x80, LENGTH = 0x000080
|
||||
RSVD (rx) : ORIGIN = 0x08004000, LENGTH = 0x00C000 - 0x004000
|
||||
FLASH (rx) : ORIGIN = 0x0800C000, LENGTH = 0x034000
|
||||
SRAM (rwx) : ORIGIN = 0x20000000, LENGTH = 0x00A000
|
||||
CCSRAM (rw) : ORIGIN = 0x10000000, LENGTH = 0x002000
|
||||
}
|
197
flight/pios/stm32f30x/link_STM32F303CCT_CC_Rev1_sections.ld
Normal file
197
flight/pios/stm32f30x/link_STM32F303CCT_CC_Rev1_sections.ld
Normal file
@ -0,0 +1,197 @@
|
||||
|
||||
/* Section Definitions */
|
||||
SECTIONS
|
||||
{
|
||||
/*
|
||||
* Vectors, code and constant data.
|
||||
*/
|
||||
.text :
|
||||
{
|
||||
PROVIDE (pios_isr_vector_table_base = .);
|
||||
KEEP(*(.cpu_vectors)) /* CPU exception vectors */
|
||||
KEEP(*(.io_vectors)) /* I/O interrupt vectors */
|
||||
*(.text .text.* .gnu.linkonce.t.*)
|
||||
*(.glue_7t) *(.glue_7)
|
||||
*(.rodata .rodata* .gnu.linkonce.r.*)
|
||||
} > FLASH
|
||||
|
||||
/*
|
||||
* Init section for UAVObjects.
|
||||
*/
|
||||
.initcalluavobj.init :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__uavobj_initcall_start = .;
|
||||
KEEP(*(.initcalluavobj.init))
|
||||
. = ALIGN(4);
|
||||
__uavobj_initcall_end = .;
|
||||
} >FLASH
|
||||
|
||||
/*
|
||||
* Module init section section
|
||||
*/
|
||||
.initcallmodule.init :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__module_initcall_start = .;
|
||||
KEEP(*(.initcallmodule.init))
|
||||
. = ALIGN(4);
|
||||
__module_initcall_end = .;
|
||||
} >FLASH
|
||||
|
||||
|
||||
/*
|
||||
* C++ exception handling.
|
||||
*/
|
||||
.ARM.extab :
|
||||
{
|
||||
*(.ARM.extab* .gnu.linkonce.armextab.*)
|
||||
} > FLASH
|
||||
.ARM.exidx :
|
||||
{
|
||||
__exidx_start = .;
|
||||
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
|
||||
__exidx_end = .;
|
||||
} > FLASH
|
||||
|
||||
/*
|
||||
* Markers for the end of the 'text' section and the in-flash start of
|
||||
* non-constant data
|
||||
*/
|
||||
. = ALIGN(4);
|
||||
_etext = .;
|
||||
_sidata = .;
|
||||
|
||||
/*
|
||||
* Board info structure, normally only generated by the bootloader but can
|
||||
* be read by the application.
|
||||
*/
|
||||
PROVIDE(pios_board_info_blob = ORIGIN(BD_INFO));
|
||||
.boardinfo :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
KEEP(*(.boardinfo))
|
||||
. = ALIGN(ORIGIN(BD_INFO)+LENGTH(BD_INFO));
|
||||
} > BD_INFO
|
||||
|
||||
/*
|
||||
* Place the IRQ/bootstrap stack at the bottom of SRAM so that an overflow
|
||||
* results in a hard fault.
|
||||
*/
|
||||
.istack (NOLOAD) :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_irq_stack_end = . ;
|
||||
*(.irqstack)
|
||||
_irq_stack_top = . ;
|
||||
} > CCSRAM
|
||||
|
||||
|
||||
/*
|
||||
* Non-const initialised data.
|
||||
*/
|
||||
.data : AT (_sidata)
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sdata = .;
|
||||
*(.data .data.*)
|
||||
. = ALIGN(4);
|
||||
_edata = . ;
|
||||
} > SRAM
|
||||
|
||||
/*
|
||||
* Uninitialised data (BSS + commons).
|
||||
*/
|
||||
.bss (NOLOAD) :
|
||||
{
|
||||
_sbss = . ;
|
||||
*(SORT_BY_ALIGNMENT(.bss*))
|
||||
*(COMMON)
|
||||
_ebss = . ;
|
||||
PROVIDE ( _end = _ebss ) ;
|
||||
} > SRAM
|
||||
|
||||
/*
|
||||
* The heap consumes the remainder of the SRAM.
|
||||
*/
|
||||
.heap (NOLOAD) :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sheap = . ;
|
||||
|
||||
/*
|
||||
* This allows us to declare an object or objects up to the minimum acceptable
|
||||
* heap size and receive a linker error if the space available for the heap is
|
||||
* not sufficient.
|
||||
*/
|
||||
*(.heap)
|
||||
|
||||
/* extend the heap up to the top of SRAM */
|
||||
. = ORIGIN(SRAM) + LENGTH(SRAM) - ABSOLUTE(_sheap);
|
||||
_eheap = .;
|
||||
} > SRAM
|
||||
|
||||
/*
|
||||
* 'Fast' memory goes in the CCM SRAM
|
||||
*/
|
||||
.fast (NOLOAD) :
|
||||
{
|
||||
_sfast = . ;
|
||||
*(.fast)
|
||||
_efast = . ;
|
||||
} > CCSRAM
|
||||
|
||||
/*
|
||||
* The fastheap consumes the remainder of the CCSRAM.
|
||||
*/
|
||||
.fastheap (NOLOAD) :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sfastheap = . ;
|
||||
|
||||
/*
|
||||
* This allows us to declare an object or objects up to the minimum acceptable
|
||||
* heap size and receive a linker error if the space available for the heap is
|
||||
* not sufficient.
|
||||
*/
|
||||
*(.fastheap)
|
||||
|
||||
/* extend the heap up to the top of SRAM */
|
||||
. = ORIGIN(CCSRAM) + LENGTH(CCSRAM) - ABSOLUTE(_sfastheap);
|
||||
_efastheap = .;
|
||||
} > CCSRAM
|
||||
|
||||
/* Stabs debugging sections. */
|
||||
.stab 0 : { *(.stab) }
|
||||
.stabstr 0 : { *(.stabstr) }
|
||||
.stab.excl 0 : { *(.stab.excl) }
|
||||
.stab.exclstr 0 : { *(.stab.exclstr) }
|
||||
.stab.index 0 : { *(.stab.index) }
|
||||
.stab.indexstr 0 : { *(.stab.indexstr) }
|
||||
.comment 0 : { *(.comment) }
|
||||
/* DWARF debug sections.
|
||||
Symbols in the DWARF debugging sections are relative to the beginning
|
||||
of the section so we begin them at 0. */
|
||||
/* DWARF 1 */
|
||||
.debug 0 : { *(.debug) }
|
||||
.line 0 : { *(.line) }
|
||||
/* GNU DWARF 1 extensions */
|
||||
.debug_srcinfo 0 : { *(.debug_srcinfo) }
|
||||
.debug_sfnames 0 : { *(.debug_sfnames) }
|
||||
/* DWARF 1.1 and DWARF 2 */
|
||||
.debug_aranges 0 : { *(.debug_aranges) }
|
||||
.debug_pubnames 0 : { *(.debug_pubnames) }
|
||||
/* DWARF 2 */
|
||||
.debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) }
|
||||
.debug_abbrev 0 : { *(.debug_abbrev) }
|
||||
.debug_line 0 : { *(.debug_line) }
|
||||
.debug_frame 0 : { *(.debug_frame) }
|
||||
.debug_str 0 : { *(.debug_str) }
|
||||
.debug_loc 0 : { *(.debug_loc) }
|
||||
.debug_macinfo 0 : { *(.debug_macinfo) }
|
||||
/* SGI/MIPS DWARF 2 extensions */
|
||||
.debug_weaknames 0 : { *(.debug_weaknames) }
|
||||
.debug_funcnames 0 : { *(.debug_funcnames) }
|
||||
.debug_typenames 0 : { *(.debug_typenames) }
|
||||
.debug_varnames 0 : { *(.debug_varnames) }
|
||||
}
|
111
flight/pios/stm32f30x/pios_bkp.c
Normal file
111
flight/pios/stm32f30x/pios_bkp.c
Normal file
@ -0,0 +1,111 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_BKP Backup SRAM functions
|
||||
* @brief Hardware abstraction layer for backup sram
|
||||
* @{
|
||||
*
|
||||
* @file pios_bkp.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2013.
|
||||
* @brief IAP functions
|
||||
* @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>
|
||||
#include <pios_bkp.h>
|
||||
#include <stm32f30x_rtc.h>
|
||||
|
||||
/****************************************************************************************
|
||||
* Header files
|
||||
****************************************************************************************/
|
||||
|
||||
/*****************************************************************************************
|
||||
* Public Definitions/Macros
|
||||
****************************************************************************************/
|
||||
|
||||
/****************************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************************/
|
||||
const uint32_t pios_bkp_registers_map[] = {
|
||||
RTC_BKP_DR0,
|
||||
RTC_BKP_DR1,
|
||||
RTC_BKP_DR2,
|
||||
RTC_BKP_DR3,
|
||||
RTC_BKP_DR4,
|
||||
RTC_BKP_DR5,
|
||||
RTC_BKP_DR6,
|
||||
RTC_BKP_DR7,
|
||||
RTC_BKP_DR8,
|
||||
RTC_BKP_DR9,
|
||||
RTC_BKP_DR10,
|
||||
RTC_BKP_DR11,
|
||||
RTC_BKP_DR12,
|
||||
RTC_BKP_DR13,
|
||||
RTC_BKP_DR14,
|
||||
RTC_BKP_DR15,
|
||||
};
|
||||
#define PIOS_BKP_REGISTERS_COUNT NELEMENTS(pios_bkp_registers_map)
|
||||
|
||||
void PIOS_BKP_Init(void)
|
||||
{
|
||||
/* Enable CRC clock */
|
||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_CRC, ENABLE);
|
||||
|
||||
/* Enable PWR and BKP clock */
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR, ENABLE);
|
||||
|
||||
/* Clear Tamper pin Event(TE) pending flag */
|
||||
RTC_ClearFlag(RTC_FLAG_TAMP1F);
|
||||
}
|
||||
|
||||
uint16_t PIOS_BKP_ReadRegister(uint32_t regnumber)
|
||||
{
|
||||
if (PIOS_BKP_REGISTERS_COUNT < regnumber) {
|
||||
PIOS_Assert(0);
|
||||
} else {
|
||||
return (uint16_t)RTC_ReadBackupRegister(pios_bkp_registers_map[regnumber]);
|
||||
}
|
||||
}
|
||||
|
||||
void PIOS_BKP_WriteRegister(uint32_t regnumber, uint16_t data)
|
||||
{
|
||||
if (PIOS_BKP_REGISTERS_COUNT < regnumber) {
|
||||
PIOS_Assert(0);
|
||||
} else {
|
||||
RTC_WriteBackupRegister(pios_bkp_registers_map[regnumber], (uint32_t)data);
|
||||
}
|
||||
}
|
||||
|
||||
void PIOS_BKP_EnableWrite(void)
|
||||
{
|
||||
/* Enable write access to Backup domain */
|
||||
PWR_BackupAccessCmd(ENABLE);
|
||||
}
|
||||
|
||||
void PIOS_BKP_DisableWrite(void)
|
||||
{
|
||||
/* Enable write access to Backup domain */
|
||||
PWR_BackupAccessCmd(DISABLE);
|
||||
}
|
||||
|
||||
|
||||
/****************************************************************************************
|
||||
* Public Data
|
||||
****************************************************************************************/
|
127
flight/pios/stm32f30x/pios_bl_helper.c
Normal file
127
flight/pios/stm32f30x/pios_bl_helper.c
Normal file
@ -0,0 +1,127 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_BOOTLOADER Functions
|
||||
* @brief HAL code to interface to the OpenPilot AHRS module
|
||||
* @{
|
||||
*
|
||||
* @file pios_bl_helper.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Bootloader Helper Functions
|
||||
* @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_BL_HELPER
|
||||
|
||||
#include <pios_board_info.h>
|
||||
#include <stm32f30x_flash.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
uint8_t *PIOS_BL_HELPER_FLASH_If_Read(uint32_t SectorAddress)
|
||||
{
|
||||
return (uint8_t *)(SectorAddress);
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT)
|
||||
|
||||
static bool erase_flash(uint32_t startAddress, uint32_t endAddress);
|
||||
|
||||
uint8_t PIOS_BL_HELPER_FLASH_Ini()
|
||||
{
|
||||
FLASH_Unlock();
|
||||
return 1;
|
||||
}
|
||||
|
||||
uint8_t PIOS_BL_HELPER_FLASH_Start()
|
||||
{
|
||||
const struct pios_board_info *bdinfo = &pios_board_info_blob;
|
||||
uint32_t startAddress = bdinfo->fw_base;
|
||||
uint32_t endAddress = bdinfo->fw_base + bdinfo->fw_size + bdinfo->desc_size;
|
||||
|
||||
bool success = erase_flash(startAddress, endAddress);
|
||||
|
||||
return (success) ? 1 : 0;
|
||||
}
|
||||
|
||||
uint8_t PIOS_BL_HELPER_FLASH_Erase_Bootloader()
|
||||
{
|
||||
/// Bootloader memory space erase
|
||||
uint32_t startAddress = BL_BANK_BASE;
|
||||
uint32_t endAddress = BL_BANK_BASE + BL_BANK_SIZE;
|
||||
|
||||
bool success = erase_flash(startAddress, endAddress);
|
||||
|
||||
return (success) ? 1 : 0;
|
||||
}
|
||||
|
||||
static bool erase_flash(uint32_t startAddress, uint32_t endAddress)
|
||||
{
|
||||
uint32_t pageAddress = startAddress;
|
||||
uint8_t fail = false;
|
||||
|
||||
while ((pageAddress < endAddress) && (fail == false)) {
|
||||
for (int retry = 0; retry < MAX_DEL_RETRYS; ++retry) {
|
||||
if (FLASH_ErasePage(pageAddress) == FLASH_COMPLETE) {
|
||||
fail = false;
|
||||
break;
|
||||
} else {
|
||||
fail = true;
|
||||
}
|
||||
}
|
||||
|
||||
pageAddress += 2048;
|
||||
}
|
||||
return !fail;
|
||||
}
|
||||
|
||||
#endif /* if defined(PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT) */
|
||||
|
||||
uint32_t PIOS_BL_HELPER_CRC_Memory_Calc()
|
||||
{
|
||||
const struct pios_board_info *bdinfo = &pios_board_info_blob;
|
||||
|
||||
PIOS_BL_HELPER_CRC_Ini();
|
||||
CRC_ResetDR();
|
||||
CRC_CalcBlockCRC((uint32_t *)bdinfo->fw_base, (bdinfo->fw_size) >> 2);
|
||||
return CRC_GetCRC();
|
||||
}
|
||||
|
||||
void PIOS_BL_HELPER_FLASH_Read_Description(uint8_t *array, uint8_t size)
|
||||
{
|
||||
const struct pios_board_info *bdinfo = &pios_board_info_blob;
|
||||
uint8_t x = 0;
|
||||
|
||||
if (size > bdinfo->desc_size) {
|
||||
size = bdinfo->desc_size;
|
||||
}
|
||||
for (uint32_t i = bdinfo->fw_base + bdinfo->fw_size; i < bdinfo->fw_base + bdinfo->fw_size + size; ++i) {
|
||||
array[x] = *PIOS_BL_HELPER_FLASH_If_Read(i);
|
||||
++x;
|
||||
}
|
||||
}
|
||||
|
||||
void PIOS_BL_HELPER_CRC_Ini()
|
||||
{
|
||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_CRC, ENABLE);
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_BL_HELPER */
|
429
flight/pios/stm32f30x/pios_can.c
Normal file
429
flight/pios/stm32f30x/pios_can.c
Normal file
@ -0,0 +1,429 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @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 */
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
178
flight/pios/stm32f30x/pios_debug.c
Normal file
178
flight/pios/stm32f30x/pios_debug.c
Normal file
@ -0,0 +1,178 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @defgroup PIOS_DEBUG Debugging Functions
|
||||
* @brief Debugging functionality
|
||||
* @{
|
||||
*
|
||||
* @file pios_debug.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2013.
|
||||
* @brief Debugging Functions
|
||||
* @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"
|
||||
|
||||
// Global variables
|
||||
const char *PIOS_DEBUG_AssertMsg = "ASSERT FAILED";
|
||||
|
||||
#ifdef PIOS_ENABLE_DEBUG_PINS
|
||||
static const struct pios_tim_channel *debug_channels;
|
||||
static uint8_t debug_num_channels;
|
||||
#endif /* PIOS_ENABLE_DEBUG_PINS */
|
||||
|
||||
/**
|
||||
* Initialise Debug-features
|
||||
*/
|
||||
void PIOS_DEBUG_Init(__attribute__((unused)) const struct pios_tim_channel *channels, __attribute__((unused)) uint8_t num_channels)
|
||||
{
|
||||
#ifdef PIOS_ENABLE_DEBUG_PINS
|
||||
PIOS_Assert(channels);
|
||||
PIOS_Assert(num_channels);
|
||||
|
||||
/* Store away the GPIOs we've been given */
|
||||
debug_channels = channels;
|
||||
debug_num_channels = num_channels;
|
||||
|
||||
/* Configure the GPIOs we've been given */
|
||||
for (uint8_t i = 0; i < num_channels; i++) {
|
||||
const struct pios_tim_channel *chan = &channels[i];
|
||||
|
||||
// Initialise pins as standard output pins
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
GPIO_StructInit(&GPIO_InitStructure);
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
|
||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_InitStructure.GPIO_Pin = chan->pin.init.GPIO_Pin;
|
||||
|
||||
/* Initialize the GPIO */
|
||||
GPIO_Init(chan->pin.gpio, &GPIO_InitStructure);
|
||||
|
||||
/* Set the pin low */
|
||||
GPIO_WriteBit(chan->pin.gpio, chan->pin.init.GPIO_Pin, Bit_RESET);
|
||||
}
|
||||
#endif // PIOS_ENABLE_DEBUG_PINS
|
||||
}
|
||||
|
||||
/**
|
||||
* Set debug-pin high
|
||||
* \param pin 0 for S1 output
|
||||
*/
|
||||
void PIOS_DEBUG_PinHigh(__attribute__((unused)) uint8_t pin)
|
||||
{
|
||||
#ifdef PIOS_ENABLE_DEBUG_PINS
|
||||
if (!debug_channels || pin >= debug_num_channels) {
|
||||
return;
|
||||
}
|
||||
|
||||
const struct pios_tim_channel *chan = &debug_channels[pin];
|
||||
|
||||
GPIO_WriteBit(chan->pin.gpio, chan->pin.init.GPIO_Pin, Bit_SET);
|
||||
|
||||
#endif // PIOS_ENABLE_DEBUG_PINS
|
||||
}
|
||||
|
||||
/**
|
||||
* Set debug-pin low
|
||||
* \param pin 0 for S1 output
|
||||
*/
|
||||
void PIOS_DEBUG_PinLow(__attribute__((unused)) uint8_t pin)
|
||||
{
|
||||
#ifdef PIOS_ENABLE_DEBUG_PINS
|
||||
if (!debug_channels || pin >= debug_num_channels) {
|
||||
return;
|
||||
}
|
||||
|
||||
const struct pios_tim_channel *chan = &debug_channels[pin];
|
||||
|
||||
GPIO_WriteBit(chan->pin.gpio, chan->pin.init.GPIO_Pin, Bit_RESET);
|
||||
|
||||
#endif // PIOS_ENABLE_DEBUG_PINS
|
||||
}
|
||||
|
||||
|
||||
void PIOS_DEBUG_PinValue8Bit(__attribute__((unused)) uint8_t value)
|
||||
{
|
||||
#ifdef PIOS_ENABLE_DEBUG_PINS
|
||||
if (!debug_channels) {
|
||||
return;
|
||||
}
|
||||
|
||||
#pragma message("This code is not portable and should be revised")
|
||||
PIOS_Assert(0);
|
||||
|
||||
uint32_t bsrr_l = (((~value) & 0x0F) << (16 + 6)) | ((value & 0x0F) << 6);
|
||||
uint32_t bsrr_h = (((~value) & 0xF0) << (16 + 6 - 4)) | ((value & 0xF0) << (6 - 4));
|
||||
|
||||
PIOS_IRQ_Disable();
|
||||
|
||||
/*
|
||||
* This is sketchy since it assumes a particular ordering
|
||||
* and bitwise layout of the channels provided to the debug code.
|
||||
*/
|
||||
// debug_channels[0].pin.gpio->BSRR = bsrr_l;
|
||||
// debug_channels[4].pin.gpio->BSRR = bsrr_h;
|
||||
|
||||
PIOS_IRQ_Enable();
|
||||
#endif // PIOS_ENABLE_DEBUG_PINS
|
||||
}
|
||||
|
||||
void PIOS_DEBUG_PinValue4BitL(__attribute__((unused)) uint8_t value)
|
||||
{
|
||||
#ifdef PIOS_ENABLE_DEBUG_PINS
|
||||
if (!debug_channels) {
|
||||
return;
|
||||
}
|
||||
|
||||
#pragma message("This code is not portable and should be revised")
|
||||
PIOS_Assert(0);
|
||||
|
||||
/*
|
||||
* This is sketchy since it assumes a particular ordering
|
||||
* and bitwise layout of the channels provided to the debug code.
|
||||
*/
|
||||
uint32_t bsrr_l = ((~(value & 0x0F) << (16 + 6))) | ((value & 0x0F) << 6);
|
||||
// debug_channels[0].pin.gpio->BSRR = bsrr_l;
|
||||
#endif // PIOS_ENABLE_DEBUG_PINS
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Report a serious error and halt
|
||||
*/
|
||||
void PIOS_DEBUG_Panic(__attribute__((unused)) const char *msg)
|
||||
{
|
||||
#ifdef PIOS_INCLUDE_DEBUG_CONSOLE
|
||||
register int *lr asm ("lr"); // Link-register holds the PC of the caller
|
||||
DEBUG_PRINTF(0, "\r%s @0x%x\r", msg, lr);
|
||||
#endif
|
||||
|
||||
// Stay put
|
||||
while (1) {
|
||||
;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
184
flight/pios/stm32f30x/pios_delay.c
Normal file
184
flight/pios/stm32f30x/pios_delay.c
Normal file
@ -0,0 +1,184 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_DELAY Delay Functions
|
||||
* @brief PiOS Delay functionality
|
||||
* @{
|
||||
*
|
||||
* @file pios_delay.c
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016.
|
||||
* Michael Smith Copyright (C) 2012
|
||||
* @brief Delay Functions
|
||||
* - Provides a micro-second granular delay using the CPU
|
||||
* cycle counter.
|
||||
* @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_DELAY
|
||||
|
||||
/* cycles per microsecond */
|
||||
static uint32_t us_ticks;
|
||||
static uint32_t raw_hz;
|
||||
|
||||
/**
|
||||
* Initialises the Timer used by PIOS_DELAY functions.
|
||||
*
|
||||
* \return always zero (success)
|
||||
*/
|
||||
|
||||
int32_t PIOS_DELAY_Init(void)
|
||||
{
|
||||
RCC_ClocksTypeDef clocks;
|
||||
|
||||
/* compute the number of system clocks per microsecond */
|
||||
RCC_GetClocksFreq(&clocks);
|
||||
us_ticks = clocks.SYSCLK_Frequency / 1000000;
|
||||
PIOS_DEBUG_Assert(us_ticks > 1);
|
||||
raw_hz = clocks.SYSCLK_Frequency;
|
||||
|
||||
/* turn on access to the DWT registers */
|
||||
CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk;
|
||||
|
||||
/* enable the CPU cycle counter */
|
||||
DWT_CTRL |= CYCCNTENA;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Waits for a specific number of uS
|
||||
*
|
||||
* Example:<BR>
|
||||
* \code
|
||||
* // Wait for 500 uS
|
||||
* PIOS_DELAY_Wait_uS(500);
|
||||
* \endcode
|
||||
* \param[in] uS delay
|
||||
* \return < 0 on errors
|
||||
*/
|
||||
int32_t PIOS_DELAY_WaituS(uint32_t uS)
|
||||
{
|
||||
uint32_t elapsed = 0;
|
||||
uint32_t last_count = PIOS_DELAY_GetRaw();
|
||||
|
||||
for (;;) {
|
||||
uint32_t current_count = PIOS_DELAY_GetRaw();
|
||||
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 / us_ticks;
|
||||
if (elapsed_uS >= uS) {
|
||||
break;
|
||||
}
|
||||
|
||||
/* reduce the delay by the elapsed time */
|
||||
uS -= elapsed_uS;
|
||||
|
||||
/* keep fractional microseconds for the next iteration */
|
||||
elapsed %= us_ticks;
|
||||
}
|
||||
|
||||
/* No error */
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Waits for a specific number of mS
|
||||
*
|
||||
* Example:<BR>
|
||||
* \code
|
||||
* // Wait for 500 mS
|
||||
* PIOS_DELAY_Wait_mS(500);
|
||||
* \endcode
|
||||
* \param[in] mS delay (1..65535 milliseconds)
|
||||
* \return < 0 on errors
|
||||
*/
|
||||
int32_t PIOS_DELAY_WaitmS(uint32_t mS)
|
||||
{
|
||||
while (mS--) {
|
||||
PIOS_DELAY_WaituS(1000);
|
||||
}
|
||||
|
||||
/* No error */
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Query the Delay timer for the current uS
|
||||
* @return A microsecond value
|
||||
*/
|
||||
uint32_t PIOS_DELAY_GetuS()
|
||||
{
|
||||
return PIOS_DELAY_GetRaw() / us_ticks;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Calculate time in microseconds since a previous time
|
||||
* @param[in] t previous time
|
||||
* @return time in us since previous time t.
|
||||
*/
|
||||
uint32_t PIOS_DELAY_GetuSSince(uint32_t t)
|
||||
{
|
||||
return PIOS_DELAY_GetuS() - t;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Get the raw delay timer frequency
|
||||
* @return raw delay timer frequency in Hz
|
||||
*/
|
||||
uint32_t PIOS_DELAY_GetRawHz()
|
||||
{
|
||||
return raw_hz;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Compare to raw times to and convert to us
|
||||
* @return A microsecond value
|
||||
*/
|
||||
uint32_t PIOS_DELAY_DiffuS(uint32_t raw)
|
||||
{
|
||||
uint32_t diff = PIOS_DELAY_GetRaw() - raw;
|
||||
|
||||
return diff / us_ticks;
|
||||
}
|
||||
|
||||
#if !defined(PIOS_EXCLUDE_ADVANCED_FEATURES)
|
||||
/**
|
||||
* @brief Subtract two raw times and convert to us.
|
||||
* @return Interval between raw times in microseconds
|
||||
*/
|
||||
uint32_t PIOS_DELAY_DiffuS2(uint32_t raw, uint32_t later)
|
||||
{
|
||||
return (later - raw) / us_ticks;
|
||||
}
|
||||
#endif /* !defined(PIOS_EXCLUDE_ADVANCED_FEATURES) */
|
||||
|
||||
#endif /* PIOS_INCLUDE_DELAY */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
326
flight/pios/stm32f30x/pios_exti.c
Normal file
326
flight/pios/stm32f30x/pios_exti.c
Normal file
@ -0,0 +1,326 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_EXTI External Interrupt Handlers
|
||||
* @brief External interrupt handler functions
|
||||
* @{
|
||||
*
|
||||
* @file pios_exti.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief External Interrupt Handlers
|
||||
* @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_EXTI
|
||||
|
||||
#define EXTI_MAX_LINES 16
|
||||
|
||||
static pios_exti_vector_t pios_exti_vector[EXTI_MAX_LINES];
|
||||
|
||||
static uint8_t PIOS_EXTI_line_to_index(uint32_t line)
|
||||
{
|
||||
switch (line) {
|
||||
case EXTI_Line0: return 0;
|
||||
|
||||
case EXTI_Line1: return 1;
|
||||
|
||||
case EXTI_Line2: return 2;
|
||||
|
||||
case EXTI_Line3: return 3;
|
||||
|
||||
case EXTI_Line4: return 4;
|
||||
|
||||
case EXTI_Line5: return 5;
|
||||
|
||||
case EXTI_Line6: return 6;
|
||||
|
||||
case EXTI_Line7: return 7;
|
||||
|
||||
case EXTI_Line8: return 8;
|
||||
|
||||
case EXTI_Line9: return 9;
|
||||
|
||||
case EXTI_Line10: return 10;
|
||||
|
||||
case EXTI_Line11: return 11;
|
||||
|
||||
case EXTI_Line12: return 12;
|
||||
|
||||
case EXTI_Line13: return 13;
|
||||
|
||||
case EXTI_Line14: return 14;
|
||||
|
||||
case EXTI_Line15: return 15;
|
||||
}
|
||||
|
||||
PIOS_Assert(0);
|
||||
return 0xFF;
|
||||
}
|
||||
|
||||
uint8_t PIOS_EXTI_gpio_port_to_exti_source_port(GPIO_TypeDef *gpio_port)
|
||||
{
|
||||
switch ((uint32_t)gpio_port) {
|
||||
case (uint32_t)GPIOA: return EXTI_PortSourceGPIOA;
|
||||
|
||||
case (uint32_t)GPIOB: return EXTI_PortSourceGPIOB;
|
||||
|
||||
case (uint32_t)GPIOC: return EXTI_PortSourceGPIOC;
|
||||
|
||||
case (uint32_t)GPIOD: return EXTI_PortSourceGPIOD;
|
||||
|
||||
case (uint32_t)GPIOE: return EXTI_PortSourceGPIOE;
|
||||
|
||||
case (uint32_t)GPIOF: return EXTI_PortSourceGPIOF;
|
||||
}
|
||||
|
||||
PIOS_Assert(0);
|
||||
return 0xFF;
|
||||
}
|
||||
|
||||
uint8_t PIOS_EXTI_gpio_pin_to_exti_source_pin(uint32_t gpio_pin)
|
||||
{
|
||||
switch ((uint32_t)gpio_pin) {
|
||||
case GPIO_Pin_0: return GPIO_PinSource0;
|
||||
|
||||
case GPIO_Pin_1: return GPIO_PinSource1;
|
||||
|
||||
case GPIO_Pin_2: return GPIO_PinSource2;
|
||||
|
||||
case GPIO_Pin_3: return GPIO_PinSource3;
|
||||
|
||||
case GPIO_Pin_4: return GPIO_PinSource4;
|
||||
|
||||
case GPIO_Pin_5: return GPIO_PinSource5;
|
||||
|
||||
case GPIO_Pin_6: return GPIO_PinSource6;
|
||||
|
||||
case GPIO_Pin_7: return GPIO_PinSource7;
|
||||
|
||||
case GPIO_Pin_8: return GPIO_PinSource8;
|
||||
|
||||
case GPIO_Pin_9: return GPIO_PinSource9;
|
||||
|
||||
case GPIO_Pin_10: return GPIO_PinSource10;
|
||||
|
||||
case GPIO_Pin_11: return GPIO_PinSource11;
|
||||
|
||||
case GPIO_Pin_12: return GPIO_PinSource12;
|
||||
|
||||
case GPIO_Pin_13: return GPIO_PinSource13;
|
||||
|
||||
case GPIO_Pin_14: return GPIO_PinSource14;
|
||||
|
||||
case GPIO_Pin_15: return GPIO_PinSource15;
|
||||
}
|
||||
|
||||
PIOS_Assert(0);
|
||||
return 0xFF;
|
||||
}
|
||||
|
||||
int32_t PIOS_EXTI_Init(const struct pios_exti_cfg *cfg)
|
||||
{
|
||||
PIOS_Assert(cfg);
|
||||
|
||||
/* Connect this config to the requested vector */
|
||||
uint8_t line_index = PIOS_EXTI_line_to_index(cfg->line);
|
||||
|
||||
if (pios_exti_vector[line_index]) {
|
||||
/* Someone else already has this mapped */
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* Bind the vector to the exti line */
|
||||
pios_exti_vector[line_index] = cfg->vector;
|
||||
|
||||
/* Initialize the GPIO pin */
|
||||
GPIO_Init(cfg->pin.gpio, (GPIO_InitTypeDef *)&cfg->pin.init);
|
||||
|
||||
/* Set up the EXTI interrupt source */
|
||||
uint8_t exti_source_port = PIOS_EXTI_gpio_port_to_exti_source_port(cfg->pin.gpio);
|
||||
/* Following is not entirely correct! There is cfg->pin.pin_source to serve this purpose, and GPIO_Pin can also contain more than one bit set */
|
||||
uint8_t exti_source_pin = PIOS_EXTI_gpio_pin_to_exti_source_pin(cfg->pin.init.GPIO_Pin);
|
||||
SYSCFG_EXTILineConfig(exti_source_port, exti_source_pin);
|
||||
EXTI_Init((EXTI_InitTypeDef *)&cfg->exti.init);
|
||||
|
||||
/* Enable the interrupt channel */
|
||||
NVIC_Init((NVIC_InitTypeDef *)&cfg->irq.init);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int32_t PIOS_EXTI_DeInit(const struct pios_exti_cfg *cfg)
|
||||
{
|
||||
uint8_t line_index = PIOS_EXTI_line_to_index(cfg->line);
|
||||
|
||||
if (pios_exti_vector[line_index] == cfg->vector) {
|
||||
EXTI_InitTypeDef disable = cfg->exti.init;
|
||||
disable.EXTI_LineCmd = DISABLE;
|
||||
|
||||
EXTI_Init(&disable);
|
||||
pios_exti_vector[line_index] = 0;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
return -1;
|
||||
}
|
||||
|
||||
static bool PIOS_EXTI_generic_irq_handler(uint8_t line_index)
|
||||
{
|
||||
if (pios_exti_vector[line_index]) {
|
||||
return pios_exti_vector[line_index]();
|
||||
}
|
||||
|
||||
/* Unconfigured interrupt just fired! */
|
||||
return false;
|
||||
}
|
||||
|
||||
/* Bind Interrupt Handlers */
|
||||
|
||||
#ifdef PIOS_INCLUDE_FREERTOS
|
||||
#define PIOS_EXTI_HANDLE_LINE(line, woken) \
|
||||
if (EXTI_GetITStatus(EXTI_Line##line) != RESET) { \
|
||||
EXTI_ClearITPendingBit(EXTI_Line##line); \
|
||||
woken = PIOS_EXTI_generic_irq_handler(line) ? pdTRUE : woken; \
|
||||
}
|
||||
#else
|
||||
#define PIOS_EXTI_HANDLE_LINE(line, woken) \
|
||||
if (EXTI_GetITStatus(EXTI_Line##line) != RESET) { \
|
||||
EXTI_ClearITPendingBit(EXTI_Line##line); \
|
||||
PIOS_EXTI_generic_irq_handler(line); \
|
||||
}
|
||||
#endif
|
||||
|
||||
static void PIOS_EXTI_0_irq_handler(void)
|
||||
{
|
||||
#ifdef PIOS_INCLUDE_FREERTOS
|
||||
portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
|
||||
#else
|
||||
bool xHigherPriorityTaskWoken;
|
||||
#endif
|
||||
PIOS_EXTI_HANDLE_LINE(0, xHigherPriorityTaskWoken);
|
||||
#ifdef PIOS_INCLUDE_FREERTOS
|
||||
portEND_SWITCHING_ISR(xHigherPriorityTaskWoken);
|
||||
#endif
|
||||
}
|
||||
void EXTI0_IRQHandler(void) __attribute__((alias("PIOS_EXTI_0_irq_handler")));
|
||||
|
||||
static void PIOS_EXTI_1_irq_handler(void)
|
||||
{
|
||||
#ifdef PIOS_INCLUDE_FREERTOS
|
||||
portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
|
||||
#else
|
||||
bool xHigherPriorityTaskWoken;
|
||||
#endif
|
||||
PIOS_EXTI_HANDLE_LINE(1, xHigherPriorityTaskWoken);
|
||||
#ifdef PIOS_INCLUDE_FREERTOS
|
||||
portEND_SWITCHING_ISR(xHigherPriorityTaskWoken);
|
||||
#endif
|
||||
}
|
||||
void EXTI1_IRQHandler(void) __attribute__((alias("PIOS_EXTI_1_irq_handler")));
|
||||
|
||||
static void PIOS_EXTI_2_irq_handler(void)
|
||||
{
|
||||
#ifdef PIOS_INCLUDE_FREERTOS
|
||||
portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
|
||||
#else
|
||||
bool xHigherPriorityTaskWoken;
|
||||
#endif
|
||||
PIOS_EXTI_HANDLE_LINE(2, xHigherPriorityTaskWoken);
|
||||
#ifdef PIOS_INCLUDE_FREERTOS
|
||||
portEND_SWITCHING_ISR(xHigherPriorityTaskWoken);
|
||||
#endif
|
||||
}
|
||||
void EXTI2_IRQHandler(void) __attribute__((alias("PIOS_EXTI_2_irq_handler")));
|
||||
|
||||
static void PIOS_EXTI_3_irq_handler(void)
|
||||
{
|
||||
#ifdef PIOS_INCLUDE_FREERTOS
|
||||
portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
|
||||
#else
|
||||
bool xHigherPriorityTaskWoken;
|
||||
#endif
|
||||
PIOS_EXTI_HANDLE_LINE(3, xHigherPriorityTaskWoken);
|
||||
#ifdef PIOS_INCLUDE_FREERTOS
|
||||
portEND_SWITCHING_ISR(xHigherPriorityTaskWoken);
|
||||
#endif
|
||||
}
|
||||
void EXTI3_IRQHandler(void) __attribute__((alias("PIOS_EXTI_3_irq_handler")));
|
||||
|
||||
static void PIOS_EXTI_4_irq_handler(void)
|
||||
{
|
||||
#ifdef PIOS_INCLUDE_FREERTOS
|
||||
portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
|
||||
#else
|
||||
bool xHigherPriorityTaskWoken;
|
||||
#endif
|
||||
PIOS_EXTI_HANDLE_LINE(4, xHigherPriorityTaskWoken);
|
||||
#ifdef PIOS_INCLUDE_FREERTOS
|
||||
portEND_SWITCHING_ISR(xHigherPriorityTaskWoken);
|
||||
#endif
|
||||
}
|
||||
void EXTI4_IRQHandler(void) __attribute__((alias("PIOS_EXTI_4_irq_handler")));
|
||||
|
||||
static void PIOS_EXTI_9_5_irq_handler(void)
|
||||
{
|
||||
#ifdef PIOS_INCLUDE_FREERTOS
|
||||
portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
|
||||
#else
|
||||
bool xHigherPriorityTaskWoken;
|
||||
#endif
|
||||
PIOS_EXTI_HANDLE_LINE(5, xHigherPriorityTaskWoken);
|
||||
PIOS_EXTI_HANDLE_LINE(6, xHigherPriorityTaskWoken);
|
||||
PIOS_EXTI_HANDLE_LINE(7, xHigherPriorityTaskWoken);
|
||||
PIOS_EXTI_HANDLE_LINE(8, xHigherPriorityTaskWoken);
|
||||
PIOS_EXTI_HANDLE_LINE(9, xHigherPriorityTaskWoken);
|
||||
#ifdef PIOS_INCLUDE_FREERTOS
|
||||
portEND_SWITCHING_ISR(xHigherPriorityTaskWoken);
|
||||
#endif
|
||||
}
|
||||
void EXTI9_5_IRQHandler(void) __attribute__((alias("PIOS_EXTI_9_5_irq_handler")));
|
||||
|
||||
static void PIOS_EXTI_15_10_irq_handler(void)
|
||||
{
|
||||
#ifdef PIOS_INCLUDE_FREERTOS
|
||||
portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
|
||||
#else
|
||||
bool xHigherPriorityTaskWoken;
|
||||
#endif
|
||||
PIOS_EXTI_HANDLE_LINE(10, xHigherPriorityTaskWoken);
|
||||
PIOS_EXTI_HANDLE_LINE(11, xHigherPriorityTaskWoken);
|
||||
PIOS_EXTI_HANDLE_LINE(12, xHigherPriorityTaskWoken);
|
||||
PIOS_EXTI_HANDLE_LINE(13, xHigherPriorityTaskWoken);
|
||||
PIOS_EXTI_HANDLE_LINE(14, xHigherPriorityTaskWoken);
|
||||
PIOS_EXTI_HANDLE_LINE(15, xHigherPriorityTaskWoken);
|
||||
#ifdef PIOS_INCLUDE_FREERTOS
|
||||
portEND_SWITCHING_ISR(xHigherPriorityTaskWoken);
|
||||
#endif
|
||||
}
|
||||
void EXTI15_10_IRQHandler(void) __attribute__((alias("PIOS_EXTI_15_10_irq_handler")));
|
||||
|
||||
#endif /* PIOS_INCLUDE_EXTI */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
304
flight/pios/stm32f30x/pios_flash_internal.c
Normal file
304
flight/pios/stm32f30x/pios_flash_internal.c
Normal file
@ -0,0 +1,304 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pios_flash_internal.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2013.
|
||||
* @brief brief goes here.
|
||||
* --
|
||||
* @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_FLASH_INTERNAL
|
||||
|
||||
#include "stm32f30x_flash.h"
|
||||
#include "pios_flash_internal_priv.h"
|
||||
#include "pios_flash.h"
|
||||
#include <stdbool.h>
|
||||
|
||||
struct device_flash_sector {
|
||||
uint32_t start;
|
||||
uint32_t size;
|
||||
uint16_t st_sector;
|
||||
};
|
||||
|
||||
static bool PIOS_Flash_Internal_GetSectorInfo(uint32_t address, uint8_t *sector_number, uint32_t *sector_start, uint32_t *sector_size)
|
||||
{
|
||||
uint16_t sector = (address - 0x08000000) / 2048;
|
||||
|
||||
if (sector <= 127) {
|
||||
/* address lies within this sector */
|
||||
*sector_number = sector;
|
||||
*sector_start = sector * 2048 + 0x08000000;
|
||||
*sector_size = 2048;
|
||||
return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
enum pios_internal_flash_dev_magic {
|
||||
PIOS_INTERNAL_FLASH_DEV_MAGIC = 0x33445902,
|
||||
};
|
||||
|
||||
struct pios_internal_flash_dev {
|
||||
enum pios_internal_flash_dev_magic magic;
|
||||
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
xSemaphoreHandle transaction_lock;
|
||||
#endif /* defined(PIOS_INCLUDE_FREERTOS) */
|
||||
};
|
||||
|
||||
static bool PIOS_Flash_Internal_Validate(struct pios_internal_flash_dev *flash_dev)
|
||||
{
|
||||
return flash_dev && (flash_dev->magic == PIOS_INTERNAL_FLASH_DEV_MAGIC);
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
static struct pios_internal_flash_dev *PIOS_Flash_Internal_alloc(void)
|
||||
{
|
||||
struct pios_internal_flash_dev *flash_dev;
|
||||
|
||||
flash_dev = (struct pios_internal_flash_dev *)pios_malloc(sizeof(*flash_dev));
|
||||
if (!flash_dev) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
flash_dev->magic = PIOS_INTERNAL_FLASH_DEV_MAGIC;
|
||||
|
||||
return flash_dev;
|
||||
}
|
||||
#else
|
||||
static struct pios_internal_flash_dev pios_internal_flash_devs[PIOS_INTERNAL_FLASH_MAX_DEVS];
|
||||
static uint8_t pios_internal_flash_num_devs;
|
||||
static struct pios_internal_flash_dev *PIOS_Flash_Internal_alloc(void)
|
||||
{
|
||||
struct pios_internal_flash_dev *flash_dev;
|
||||
|
||||
if (pios_internal_flash_num_devs >= PIOS_INTERNAL_FLASH_MAX_DEVS) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
flash_dev = &pios_internal_flash_devs[pios_internal_flash_num_devs++];
|
||||
flash_dev->magic = PIOS_INTERNAL_FLASH_DEV_MAGIC;
|
||||
|
||||
return flash_dev;
|
||||
}
|
||||
|
||||
#endif /* defined(PIOS_INCLUDE_FREERTOS) */
|
||||
|
||||
int32_t PIOS_Flash_Internal_Init(uintptr_t *flash_id, __attribute__((unused)) const struct pios_flash_internal_cfg *cfg)
|
||||
{
|
||||
struct pios_internal_flash_dev *flash_dev;
|
||||
|
||||
flash_dev = PIOS_Flash_Internal_alloc();
|
||||
if (flash_dev == NULL) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
flash_dev->transaction_lock = xSemaphoreCreateMutex();
|
||||
#endif /* defined(PIOS_INCLUDE_FREERTOS) */
|
||||
|
||||
*flash_id = (uintptr_t)flash_dev;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**********************************
|
||||
*
|
||||
* Provide a PIOS flash driver API
|
||||
*
|
||||
*********************************/
|
||||
#include "pios_flash.h"
|
||||
|
||||
static int32_t PIOS_Flash_Internal_StartTransaction(uintptr_t flash_id)
|
||||
{
|
||||
struct pios_internal_flash_dev *flash_dev = (struct pios_internal_flash_dev *)flash_id;
|
||||
|
||||
if (!PIOS_Flash_Internal_Validate(flash_dev)) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
if (xSemaphoreTake(flash_dev->transaction_lock, portMAX_DELAY) != pdTRUE) {
|
||||
return -2;
|
||||
}
|
||||
#endif /* defined(PIOS_INCLUDE_FREERTOS) */
|
||||
|
||||
/* Unlock the internal flash so we can write to it */
|
||||
FLASH_Unlock();
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int32_t PIOS_Flash_Internal_EndTransaction(uintptr_t flash_id)
|
||||
{
|
||||
struct pios_internal_flash_dev *flash_dev = (struct pios_internal_flash_dev *)flash_id;
|
||||
|
||||
if (!PIOS_Flash_Internal_Validate(flash_dev)) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
if (xSemaphoreGive(flash_dev->transaction_lock) != pdTRUE) {
|
||||
return -2;
|
||||
}
|
||||
#endif /* defined(PIOS_INCLUDE_FREERTOS) */
|
||||
|
||||
/* Lock the internal flash again so we can no longer write to it */
|
||||
FLASH_Lock();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int32_t PIOS_Flash_Internal_EraseSector(uintptr_t flash_id, uint32_t addr)
|
||||
{
|
||||
struct pios_internal_flash_dev *flash_dev = (struct pios_internal_flash_dev *)flash_id;
|
||||
|
||||
if (!PIOS_Flash_Internal_Validate(flash_dev)) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
uint8_t sector_number;
|
||||
uint32_t sector_start;
|
||||
uint32_t sector_size;
|
||||
if (!PIOS_Flash_Internal_GetSectorInfo(addr,
|
||||
§or_number,
|
||||
§or_start,
|
||||
§or_size)) {
|
||||
/* We're asking for an invalid flash address */
|
||||
return -2;
|
||||
}
|
||||
|
||||
if (FLASH_ErasePage(sector_start) != FLASH_COMPLETE) {
|
||||
return -3;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int32_t PIOS_Flash_Internal_WriteData(uintptr_t flash_id, uint32_t addr, uint8_t *data, uint16_t len)
|
||||
{
|
||||
PIOS_Assert(data);
|
||||
|
||||
struct pios_internal_flash_dev *flash_dev = (struct pios_internal_flash_dev *)flash_id;
|
||||
|
||||
if (!PIOS_Flash_Internal_Validate(flash_dev)) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
uint8_t sector_number;
|
||||
uint32_t sector_start;
|
||||
uint32_t sector_size;
|
||||
uint32_t hword_data;
|
||||
uint32_t offset;
|
||||
|
||||
/* Ensure that the base address is in a valid sector */
|
||||
if (!PIOS_Flash_Internal_GetSectorInfo(addr,
|
||||
§or_number,
|
||||
§or_start,
|
||||
§or_size)) {
|
||||
/* We're asking for an invalid flash address */
|
||||
return -2;
|
||||
}
|
||||
|
||||
/* Ensure that the entire write occurs within the same sector */
|
||||
if ((uintptr_t)addr + len > sector_start + sector_size) {
|
||||
/* Write crosses the end of the sector */
|
||||
return -3;
|
||||
}
|
||||
|
||||
/* Write the data */
|
||||
uint32_t temp_addr = addr;
|
||||
uint16_t numberOfhWords = len / 2;
|
||||
uint16_t x = 0;
|
||||
FLASH_Status status;
|
||||
for (x = 0; x < numberOfhWords; ++x) {
|
||||
offset = 2 * x;
|
||||
hword_data = (data[offset + 1] << 8) | data[offset];
|
||||
|
||||
if (hword_data != *(uint16_t *)(temp_addr + offset)) {
|
||||
status = FLASH_ProgramHalfWord(temp_addr + offset, hword_data);
|
||||
} else {
|
||||
status = FLASH_COMPLETE;
|
||||
}
|
||||
PIOS_Assert(status == FLASH_COMPLETE);
|
||||
}
|
||||
|
||||
uint16_t mod = len % 2;
|
||||
if (mod == 1) {
|
||||
offset = 2 * x;
|
||||
hword_data = 0xFF00 | data[offset];
|
||||
if (hword_data != *(uint16_t *)(temp_addr + offset)) {
|
||||
status = FLASH_ProgramHalfWord(temp_addr + offset, hword_data);
|
||||
} else {
|
||||
status = FLASH_COMPLETE;
|
||||
}
|
||||
PIOS_Assert(status == FLASH_COMPLETE);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int32_t PIOS_Flash_Internal_ReadData(uintptr_t flash_id, uint32_t addr, uint8_t *data, uint16_t len)
|
||||
{
|
||||
PIOS_Assert(data);
|
||||
|
||||
struct pios_internal_flash_dev *flash_dev = (struct pios_internal_flash_dev *)flash_id;
|
||||
|
||||
if (!PIOS_Flash_Internal_Validate(flash_dev)) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
uint8_t sector_number;
|
||||
uint32_t sector_start;
|
||||
uint32_t sector_size;
|
||||
|
||||
/* Ensure that the base address is in a valid sector */
|
||||
if (!PIOS_Flash_Internal_GetSectorInfo(addr,
|
||||
§or_number,
|
||||
§or_start,
|
||||
§or_size)) {
|
||||
/* We're asking for an invalid flash address */
|
||||
return -2;
|
||||
}
|
||||
|
||||
/* Ensure that the entire read occurs within the same sector */
|
||||
if ((uintptr_t)addr + len > sector_start + sector_size) {
|
||||
/* Read crosses the end of the sector */
|
||||
return -3;
|
||||
}
|
||||
|
||||
/* Read the data into the buffer directly */
|
||||
memcpy(data, (void *)addr, len);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/* Provide a flash driver to external drivers */
|
||||
const struct pios_flash_driver pios_internal_flash_driver = {
|
||||
.start_transaction = PIOS_Flash_Internal_StartTransaction,
|
||||
.end_transaction = PIOS_Flash_Internal_EndTransaction,
|
||||
.erase_sector = PIOS_Flash_Internal_EraseSector,
|
||||
.write_data = PIOS_Flash_Internal_WriteData,
|
||||
.read_data = PIOS_Flash_Internal_ReadData,
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_FLASH_INTERNAL */
|
170
flight/pios/stm32f30x/pios_gpio.c
Normal file
170
flight/pios/stm32f30x/pios_gpio.c
Normal file
@ -0,0 +1,170 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_GPIO GPIO Functions
|
||||
* @brief STM32 Hardware GPIO handling code
|
||||
* @{
|
||||
*
|
||||
* @file pios_gpio.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief GPIO functions, init, toggle, on & off.
|
||||
* @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_GPIO
|
||||
|
||||
#include <pios_gpio_priv.h>
|
||||
|
||||
/**
|
||||
* Initialises all the GPIO's
|
||||
*/
|
||||
int32_t PIOS_GPIO_Init(uint32_t *gpios_dev_id, const struct pios_gpio_cfg *cfg)
|
||||
{
|
||||
PIOS_Assert(cfg);
|
||||
*gpios_dev_id = (uint32_t)cfg;
|
||||
|
||||
for (uint8_t i = 0; i < cfg->num_gpios; i++) {
|
||||
const struct pios_gpio *gpio = &(cfg->gpios[i]);
|
||||
|
||||
/* Enable the peripheral clock for the GPIO */
|
||||
switch ((uint32_t)gpio->pin.gpio) {
|
||||
case (uint32_t)GPIOA:
|
||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOA, ENABLE);
|
||||
break;
|
||||
case (uint32_t)GPIOB:
|
||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOB, ENABLE);
|
||||
break;
|
||||
case (uint32_t)GPIOC:
|
||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOC, ENABLE);
|
||||
break;
|
||||
case (uint32_t)GPIOD:
|
||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOD, ENABLE);
|
||||
break;
|
||||
case (uint32_t)GPIOE:
|
||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOE, ENABLE);
|
||||
break;
|
||||
case (uint32_t)GPIOF:
|
||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOF, ENABLE);
|
||||
break;
|
||||
default:
|
||||
PIOS_Assert(0);
|
||||
break;
|
||||
}
|
||||
|
||||
if (gpio->remap) {
|
||||
GPIO_PinAFConfig(gpio->pin.gpio, gpio->pin.init.GPIO_Pin, gpio->remap);
|
||||
}
|
||||
|
||||
GPIO_Init(gpio->pin.gpio, &((struct pios_gpio *)gpio)->pin.init);
|
||||
|
||||
PIOS_GPIO_Off(*gpios_dev_id, i);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Turn on GPIO
|
||||
* \param[in] GPIO GPIO id
|
||||
*/
|
||||
void PIOS_GPIO_On(uint32_t gpios_dev_id, uint8_t gpio_id)
|
||||
{
|
||||
const struct pios_gpio_cfg *gpio_cfg = (const struct pios_gpio_cfg *)gpios_dev_id;
|
||||
|
||||
PIOS_Assert(gpio_cfg);
|
||||
|
||||
if (gpio_id >= gpio_cfg->num_gpios) {
|
||||
/* GPIO index out of range */
|
||||
return;
|
||||
}
|
||||
|
||||
const struct pios_gpio *gpio = &(gpio_cfg->gpios[gpio_id]);
|
||||
|
||||
if (gpio->active_low) {
|
||||
GPIO_ResetBits(gpio->pin.gpio, gpio->pin.init.GPIO_Pin);
|
||||
} else {
|
||||
GPIO_SetBits(gpio->pin.gpio, gpio->pin.init.GPIO_Pin);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Turn off GPIO
|
||||
* \param[in] GPIO GPIO id
|
||||
*/
|
||||
void PIOS_GPIO_Off(uint32_t gpios_dev_id, uint8_t gpio_id)
|
||||
{
|
||||
const struct pios_gpio_cfg *gpio_cfg = (const struct pios_gpio_cfg *)gpios_dev_id;
|
||||
|
||||
PIOS_Assert(gpio_cfg);
|
||||
|
||||
if (gpio_id >= gpio_cfg->num_gpios) {
|
||||
/* GPIO index out of range */
|
||||
return;
|
||||
}
|
||||
|
||||
const struct pios_gpio *gpio = &(gpio_cfg->gpios[gpio_id]);
|
||||
|
||||
if (gpio->active_low) {
|
||||
GPIO_SetBits(gpio->pin.gpio, gpio->pin.init.GPIO_Pin);
|
||||
} else {
|
||||
GPIO_ResetBits(gpio->pin.gpio, gpio->pin.init.GPIO_Pin);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Toggle GPIO on/off
|
||||
* \param[in] GPIO GPIO id
|
||||
*/
|
||||
void PIOS_GPIO_Toggle(uint32_t gpios_dev_id, uint8_t gpio_id)
|
||||
{
|
||||
const struct pios_gpio_cfg *gpio_cfg = (const struct pios_gpio_cfg *)gpios_dev_id;
|
||||
|
||||
PIOS_Assert(gpio_cfg);
|
||||
|
||||
if (gpio_id >= gpio_cfg->num_gpios) {
|
||||
/* GPIO index out of range */
|
||||
return;
|
||||
}
|
||||
|
||||
const struct pios_gpio *gpio = &(gpio_cfg->gpios[gpio_id]);
|
||||
|
||||
if (GPIO_ReadOutputDataBit(gpio->pin.gpio, gpio->pin.init.GPIO_Pin) == Bit_SET) {
|
||||
if (gpio->active_low) {
|
||||
PIOS_GPIO_On(gpios_dev_id, gpio_id);
|
||||
} else {
|
||||
PIOS_GPIO_Off(gpios_dev_id, gpio_id);
|
||||
}
|
||||
} else {
|
||||
if (gpio->active_low) {
|
||||
PIOS_GPIO_Off(gpios_dev_id, gpio_id);
|
||||
} else {
|
||||
PIOS_GPIO_On(gpios_dev_id, gpio_id);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_GPIO */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
924
flight/pios/stm32f30x/pios_i2c.c
Normal file
924
flight/pios/stm32f30x/pios_i2c.c
Normal file
@ -0,0 +1,924 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_I2C I2C Functions
|
||||
* @brief STM32F4xx Hardware dependent I2C functionality
|
||||
* @{
|
||||
*
|
||||
* @file pios_i2c.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2014
|
||||
* @author dRonin, http://dronin.org, Copyright (C) 2016
|
||||
* @brief I2C Enable/Disable routines
|
||||
* @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
|
||||
*/
|
||||
|
||||
/* Project Includes */
|
||||
#include "pios.h"
|
||||
|
||||
#if defined(PIOS_INCLUDE_I2C)
|
||||
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
#define USE_FREERTOS
|
||||
#endif
|
||||
|
||||
#include <pios_i2c_priv.h>
|
||||
|
||||
enum i2c_adapter_state {
|
||||
I2C_STATE_FSM_FAULT = 0, /* Must be zero so undefined transitions land here */
|
||||
|
||||
I2C_STATE_BUS_ERROR,
|
||||
|
||||
I2C_STATE_STOPPED,
|
||||
I2C_STATE_STOPPING,
|
||||
I2C_STATE_STARTING,
|
||||
|
||||
I2C_STATE_R_MORE_TXN_ADDR,
|
||||
I2C_STATE_R_MORE_TXN_PRE_ONE,
|
||||
I2C_STATE_R_MORE_TXN_PRE_FIRST,
|
||||
I2C_STATE_R_MORE_TXN_PRE_MIDDLE,
|
||||
I2C_STATE_R_MORE_TXN_PRE_LAST,
|
||||
I2C_STATE_R_MORE_TXN_POST_LAST,
|
||||
|
||||
I2C_STATE_R_LAST_TXN_ADDR,
|
||||
I2C_STATE_R_LAST_TXN_PRE_ONE,
|
||||
I2C_STATE_R_LAST_TXN_PRE_FIRST,
|
||||
I2C_STATE_R_LAST_TXN_PRE_MIDDLE,
|
||||
I2C_STATE_R_LAST_TXN_PRE_LAST,
|
||||
I2C_STATE_R_LAST_TXN_POST_LAST,
|
||||
|
||||
I2C_STATE_W_MORE_TXN_ADDR,
|
||||
I2C_STATE_W_MORE_TXN_MIDDLE,
|
||||
I2C_STATE_W_MORE_TXN_LAST,
|
||||
|
||||
I2C_STATE_W_LAST_TXN_ADDR,
|
||||
I2C_STATE_W_LAST_TXN_MIDDLE,
|
||||
I2C_STATE_W_LAST_TXN_LAST,
|
||||
|
||||
I2C_STATE_NACK,
|
||||
|
||||
I2C_STATE_NUM_STATES /* Must be last */
|
||||
};
|
||||
|
||||
enum i2c_adapter_event {
|
||||
I2C_EVENT_START,
|
||||
I2C_EVENT_RECEIVER_BUFFER_NOT_EMPTY,
|
||||
I2C_EVENT_TRANSMIT_BUFFER_EMPTY,
|
||||
I2C_EVENT_TRANSFER_COMPLETE,
|
||||
I2C_EVENT_STOP,
|
||||
I2C_EVENT_NACK,
|
||||
I2C_EVENT_BUS_ERROR,
|
||||
I2C_EVENT_STOPPED,
|
||||
I2C_EVENT_AUTO,
|
||||
|
||||
I2C_EVENT_NUM_EVENTS /* Must be last */
|
||||
};
|
||||
|
||||
/* dirty hack to keep compatible with enum in pios_i2c_priv.h */
|
||||
#define I2C_STATE_WRITE_BYTE I2C_STATE_W_MORE_TXN_ADDR
|
||||
#define I2C_STATE_READ_BYTE I2C_STATE_W_MORE_TXN_MIDDLE
|
||||
#define I2C_STATE_TRANSFER_COMPLETE I2C_STATE_W_MORE_TXN_LAST
|
||||
|
||||
// #define I2C_HALT_ON_ERRORS
|
||||
|
||||
#if defined(PIOS_I2C_DIAGNOSTICS)
|
||||
static struct pios_i2c_fault_history i2c_adapter_fault_history;
|
||||
|
||||
static volatile uint32_t i2c_evirq_history[I2C_LOG_DEPTH];
|
||||
static volatile uint8_t i2c_evirq_history_pointer;
|
||||
|
||||
static volatile uint32_t i2c_erirq_history[I2C_LOG_DEPTH];
|
||||
static volatile uint8_t i2c_erirq_history_pointer;
|
||||
|
||||
static volatile uint8_t i2c_state_history[I2C_LOG_DEPTH];
|
||||
static volatile uint8_t i2c_state_history_pointer;
|
||||
|
||||
static volatile uint8_t i2c_state_event_history[I2C_LOG_DEPTH];
|
||||
static volatile uint8_t i2c_state_event_history_pointer;
|
||||
|
||||
static uint32_t i2c_fsm_fault_count;
|
||||
static uint32_t i2c_bad_event_counter;
|
||||
static uint32_t i2c_error_interrupt_counter;
|
||||
static uint32_t i2c_nack_counter;
|
||||
static uint32_t i2c_timeout_counter;
|
||||
#endif
|
||||
|
||||
static void go_fsm_fault(struct pios_i2c_adapter *i2c_adapter, bool *woken);
|
||||
static void go_bus_error(struct pios_i2c_adapter *i2c_adapter, bool *woken);
|
||||
static void go_stopped(struct pios_i2c_adapter *i2c_adapter, bool *woken);
|
||||
static void go_starting(struct pios_i2c_adapter *i2c_adapter, bool *woken);
|
||||
static void go_write_byte(struct pios_i2c_adapter *i2c_adapter, bool *woken);
|
||||
static void go_read_byte(struct pios_i2c_adapter *i2c_adapter, bool *woken);
|
||||
static void go_transfer_complete(struct pios_i2c_adapter *i2c_adapter, bool *woken);
|
||||
static void go_nack(struct pios_i2c_adapter *i2c_adapter, bool *woken);
|
||||
|
||||
struct i2c_adapter_transition {
|
||||
void (*entry_fn)(struct pios_i2c_adapter *i2c_adapter, bool *woken);
|
||||
enum i2c_adapter_state next_state[I2C_EVENT_NUM_EVENTS];
|
||||
};
|
||||
|
||||
static void i2c_adapter_process_auto(struct pios_i2c_adapter *i2c_adapter, bool *woken);
|
||||
static void i2c_adapter_inject_event(struct pios_i2c_adapter *i2c_adapter, enum i2c_adapter_event event, bool *woken);
|
||||
static void i2c_adapter_fsm_init(struct pios_i2c_adapter *i2c_adapter);
|
||||
static void i2c_adapter_reset_bus(struct pios_i2c_adapter *i2c_adapter);
|
||||
static bool i2c_adapter_callback_handler(struct pios_i2c_adapter *i2c_adapter, bool *woken);
|
||||
|
||||
#if defined(PIOS_I2C_DIAGNOSTICS)
|
||||
static void i2c_adapter_log_fault(struct pios_i2c_adapter *i2c_adapter, enum pios_i2c_error_type type);
|
||||
#endif
|
||||
|
||||
static const struct i2c_adapter_transition i2c_adapter_transitions[I2C_STATE_NUM_STATES] = {
|
||||
[I2C_STATE_FSM_FAULT] = {
|
||||
.entry_fn = go_fsm_fault,
|
||||
.next_state = {
|
||||
[I2C_EVENT_AUTO] = I2C_STATE_STOPPED,
|
||||
},
|
||||
},
|
||||
[I2C_STATE_BUS_ERROR] = {
|
||||
.entry_fn = go_bus_error,
|
||||
.next_state = {
|
||||
[I2C_EVENT_AUTO] = I2C_STATE_STOPPED,
|
||||
},
|
||||
},
|
||||
|
||||
[I2C_STATE_STOPPED] = {
|
||||
.entry_fn = go_stopped,
|
||||
.next_state = {
|
||||
[I2C_EVENT_START] = I2C_STATE_STARTING,
|
||||
[I2C_EVENT_BUS_ERROR] = I2C_STATE_BUS_ERROR,
|
||||
},
|
||||
},
|
||||
|
||||
[I2C_STATE_STARTING] = {
|
||||
.entry_fn = go_starting,
|
||||
.next_state = {
|
||||
[I2C_EVENT_TRANSMIT_BUFFER_EMPTY] = I2C_STATE_WRITE_BYTE,
|
||||
[I2C_EVENT_RECEIVER_BUFFER_NOT_EMPTY] = I2C_STATE_READ_BYTE,
|
||||
[I2C_EVENT_NACK] = I2C_STATE_NACK,
|
||||
[I2C_EVENT_BUS_ERROR] = I2C_STATE_BUS_ERROR,
|
||||
},
|
||||
},
|
||||
|
||||
[I2C_STATE_WRITE_BYTE] = {
|
||||
.entry_fn = go_write_byte,
|
||||
.next_state = {
|
||||
[I2C_EVENT_TRANSMIT_BUFFER_EMPTY] = I2C_STATE_WRITE_BYTE,
|
||||
[I2C_EVENT_RECEIVER_BUFFER_NOT_EMPTY] = I2C_STATE_READ_BYTE,
|
||||
[I2C_EVENT_TRANSFER_COMPLETE] = I2C_STATE_TRANSFER_COMPLETE,
|
||||
[I2C_EVENT_STOP] = I2C_STATE_STOPPED,
|
||||
[I2C_EVENT_BUS_ERROR] = I2C_STATE_BUS_ERROR,
|
||||
},
|
||||
},
|
||||
|
||||
[I2C_STATE_READ_BYTE] = {
|
||||
.entry_fn = go_read_byte,
|
||||
.next_state = {
|
||||
[I2C_EVENT_TRANSMIT_BUFFER_EMPTY] = I2C_STATE_WRITE_BYTE,
|
||||
[I2C_EVENT_RECEIVER_BUFFER_NOT_EMPTY] = I2C_STATE_READ_BYTE,
|
||||
[I2C_EVENT_TRANSFER_COMPLETE] = I2C_STATE_TRANSFER_COMPLETE,
|
||||
[I2C_EVENT_STOP] = I2C_STATE_STOPPED,
|
||||
[I2C_EVENT_BUS_ERROR] = I2C_STATE_BUS_ERROR,
|
||||
},
|
||||
},
|
||||
|
||||
[I2C_STATE_TRANSFER_COMPLETE] = {
|
||||
.entry_fn = go_transfer_complete,
|
||||
.next_state = {
|
||||
[I2C_EVENT_AUTO] = I2C_STATE_STARTING,
|
||||
[I2C_EVENT_BUS_ERROR] = I2C_STATE_BUS_ERROR,
|
||||
},
|
||||
},
|
||||
|
||||
[I2C_STATE_NACK] = {
|
||||
.entry_fn = go_nack,
|
||||
.next_state = {
|
||||
[I2C_EVENT_AUTO] = I2C_STATE_STOPPED,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static void go_fsm_fault(struct pios_i2c_adapter *i2c_adapter, __attribute__((unused)) bool *woken)
|
||||
{
|
||||
#if defined(I2C_HALT_ON_ERRORS)
|
||||
PIOS_DEBUG_Assert(0);
|
||||
#endif
|
||||
/* Note that this transfer has hit a bus error */
|
||||
i2c_adapter->bus_error = true;
|
||||
|
||||
i2c_adapter_reset_bus(i2c_adapter);
|
||||
}
|
||||
|
||||
static void go_bus_error(struct pios_i2c_adapter *i2c_adapter, __attribute__((unused)) bool *woken)
|
||||
{
|
||||
/* Note that this transfer has hit a bus error */
|
||||
i2c_adapter->bus_error = true;
|
||||
|
||||
i2c_adapter_reset_bus(i2c_adapter);
|
||||
}
|
||||
|
||||
static void go_stopped(struct pios_i2c_adapter *i2c_adapter, bool *woken)
|
||||
{
|
||||
I2C_ITConfig(i2c_adapter->cfg->regs, I2C_IT_ERRI | I2C_IT_TCI | I2C_IT_NACKI | I2C_IT_RXI | I2C_IT_STOPI | I2C_IT_TXI, DISABLE);
|
||||
|
||||
if (i2c_adapter->callback) {
|
||||
i2c_adapter_callback_handler(i2c_adapter, woken);
|
||||
} else {
|
||||
#ifdef USE_FREERTOS
|
||||
signed portBASE_TYPE pxHigherPriorityTaskWoken = pdFALSE;
|
||||
if (xSemaphoreGiveFromISR(i2c_adapter->sem_ready, &pxHigherPriorityTaskWoken) != pdTRUE) {
|
||||
#if defined(I2C_HALT_ON_ERRORS)
|
||||
PIOS_DEBUG_Assert(0);
|
||||
#endif
|
||||
}
|
||||
if (pxHigherPriorityTaskWoken == pdTRUE) {
|
||||
*woken = true;
|
||||
}
|
||||
#endif /* USE_FREERTOS */
|
||||
}
|
||||
}
|
||||
|
||||
static void go_starting(struct pios_i2c_adapter *i2c_adapter, __attribute__((unused)) bool *woken)
|
||||
{
|
||||
PIOS_DEBUG_Assert(i2c_adapter->active_txn);
|
||||
PIOS_DEBUG_Assert(i2c_adapter->active_txn <= i2c_adapter->last_txn);
|
||||
PIOS_DEBUG_Assert(i2c_adapter->active_txn->len <= 255); // FIXME: implement this using TCR
|
||||
|
||||
i2c_adapter->active_byte = &(i2c_adapter->active_txn->buf[0]);
|
||||
i2c_adapter->last_byte = &(i2c_adapter->active_txn->buf[i2c_adapter->active_txn->len - 1]);
|
||||
|
||||
I2C_ITConfig(i2c_adapter->cfg->regs, I2C_IT_ERRI | I2C_IT_TCI | I2C_IT_NACKI | I2C_IT_RXI | I2C_IT_STOPI | I2C_IT_TXI, ENABLE);
|
||||
|
||||
I2C_TransferHandling(
|
||||
i2c_adapter->cfg->regs,
|
||||
(i2c_adapter->active_txn->addr << 1),
|
||||
i2c_adapter->active_txn->len,
|
||||
i2c_adapter->active_txn == i2c_adapter->last_txn ? I2C_AutoEnd_Mode : I2C_SoftEnd_Mode,
|
||||
i2c_adapter->active_txn->rw == PIOS_I2C_TXN_WRITE ? I2C_Generate_Start_Write : I2C_Generate_Start_Read);
|
||||
}
|
||||
|
||||
static void go_write_byte(struct pios_i2c_adapter *i2c_adapter, __attribute__((unused)) bool *woken)
|
||||
{
|
||||
PIOS_DEBUG_Assert(i2c_adapter->active_txn);
|
||||
PIOS_DEBUG_Assert(i2c_adapter->active_txn <= i2c_adapter->last_txn);
|
||||
|
||||
I2C_SendData(i2c_adapter->cfg->regs, *(i2c_adapter->active_byte));
|
||||
|
||||
/* Move to the next byte */
|
||||
i2c_adapter->active_byte++;
|
||||
PIOS_DEBUG_Assert(i2c_adapter->active_byte <= i2c_adapter->last_byte);
|
||||
}
|
||||
|
||||
static void go_read_byte(struct pios_i2c_adapter *i2c_adapter, __attribute__((unused)) bool *woken)
|
||||
{
|
||||
PIOS_DEBUG_Assert(i2c_adapter->active_txn);
|
||||
PIOS_DEBUG_Assert(i2c_adapter->active_txn <= i2c_adapter->last_txn);
|
||||
|
||||
*(i2c_adapter->active_byte) = I2C_ReceiveData(i2c_adapter->cfg->regs);
|
||||
|
||||
/* Move to the next byte */
|
||||
i2c_adapter->active_byte++;
|
||||
PIOS_DEBUG_Assert(i2c_adapter->active_byte <= i2c_adapter->last_byte);
|
||||
}
|
||||
|
||||
static void go_transfer_complete(struct pios_i2c_adapter *i2c_adapter, __attribute__((unused)) bool *woken)
|
||||
{
|
||||
/* Move to the next transaction */
|
||||
i2c_adapter->active_txn++;
|
||||
PIOS_DEBUG_Assert(i2c_adapter->active_txn <= i2c_adapter->last_txn);
|
||||
}
|
||||
|
||||
static void go_nack(struct pios_i2c_adapter *i2c_adapter, __attribute__((unused)) bool *woken)
|
||||
{
|
||||
i2c_adapter->nack = true;
|
||||
I2C_ITConfig(i2c_adapter->cfg->regs, I2C_IT_ERRI | I2C_IT_TCI | I2C_IT_NACKI | I2C_IT_RXI | I2C_IT_STOPI | I2C_IT_TXI, DISABLE);
|
||||
I2C_AcknowledgeConfig(i2c_adapter->cfg->regs, DISABLE);
|
||||
I2C_GenerateSTOP(i2c_adapter->cfg->regs, ENABLE);
|
||||
}
|
||||
|
||||
static void i2c_adapter_inject_event(struct pios_i2c_adapter *i2c_adapter, enum i2c_adapter_event event, bool *woken)
|
||||
{
|
||||
#if defined(PIOS_I2C_DIAGNOSTICS)
|
||||
i2c_state_event_history[i2c_state_event_history_pointer] = event;
|
||||
i2c_state_event_history_pointer = (i2c_state_event_history_pointer + 1) % I2C_LOG_DEPTH;
|
||||
|
||||
i2c_state_history[i2c_state_history_pointer] = i2c_adapter->curr_state;
|
||||
i2c_state_history_pointer = (i2c_state_history_pointer + 1) % I2C_LOG_DEPTH;
|
||||
|
||||
if (i2c_adapter_transitions[i2c_adapter->curr_state].next_state[event] == I2C_STATE_FSM_FAULT) {
|
||||
i2c_adapter_log_fault(i2c_adapter, PIOS_I2C_ERROR_FSM);
|
||||
}
|
||||
#endif
|
||||
/*
|
||||
* Move to the next state
|
||||
*
|
||||
* This is done prior to calling the new state's entry function to
|
||||
* guarantee that the entry function never depends on the previous
|
||||
* state. This way, it cannot ever know what the previous state was.
|
||||
*/
|
||||
enum i2c_adapter_state prev_state = i2c_adapter->curr_state;
|
||||
if (prev_state) {
|
||||
;
|
||||
}
|
||||
|
||||
i2c_adapter->curr_state = i2c_adapter_transitions[i2c_adapter->curr_state].next_state[event];
|
||||
|
||||
/* Call the entry function (if any) for the next state. */
|
||||
if (i2c_adapter_transitions[i2c_adapter->curr_state].entry_fn) {
|
||||
i2c_adapter_transitions[i2c_adapter->curr_state].entry_fn(i2c_adapter, woken);
|
||||
}
|
||||
|
||||
/* Process any AUTO transitions in the FSM */
|
||||
i2c_adapter_process_auto(i2c_adapter, woken);
|
||||
}
|
||||
|
||||
static void i2c_adapter_process_auto(struct pios_i2c_adapter *i2c_adapter, bool *woken)
|
||||
{
|
||||
enum i2c_adapter_state prev_state = i2c_adapter->curr_state;
|
||||
|
||||
if (prev_state) {
|
||||
;
|
||||
}
|
||||
|
||||
while (i2c_adapter_transitions[i2c_adapter->curr_state].next_state[I2C_EVENT_AUTO]) {
|
||||
i2c_adapter->curr_state = i2c_adapter_transitions[i2c_adapter->curr_state].next_state[I2C_EVENT_AUTO];
|
||||
|
||||
/* Call the entry function (if any) for the next state. */
|
||||
if (i2c_adapter_transitions[i2c_adapter->curr_state].entry_fn) {
|
||||
i2c_adapter_transitions[i2c_adapter->curr_state].entry_fn(i2c_adapter, woken);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void i2c_adapter_fsm_init(struct pios_i2c_adapter *i2c_adapter)
|
||||
{
|
||||
i2c_adapter_reset_bus(i2c_adapter);
|
||||
i2c_adapter->curr_state = I2C_STATE_STOPPED;
|
||||
}
|
||||
|
||||
static void i2c_adapter_reset_bus(struct pios_i2c_adapter *i2c_adapter)
|
||||
{
|
||||
uint8_t retry_count = 0;
|
||||
uint8_t retry_count_clk = 0;
|
||||
static const uint8_t MAX_I2C_RETRY_COUNT = 10;
|
||||
|
||||
/* Reset the I2C block */
|
||||
I2C_DeInit(i2c_adapter->cfg->regs);
|
||||
|
||||
/* Make sure the bus is free by clocking it until any slaves release the bus. */
|
||||
GPIO_InitTypeDef scl_gpio_init;
|
||||
scl_gpio_init = i2c_adapter->cfg->scl.init;
|
||||
scl_gpio_init.GPIO_Mode = GPIO_Mode_OUT;
|
||||
GPIO_SetBits(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin);
|
||||
GPIO_Init(i2c_adapter->cfg->scl.gpio, &scl_gpio_init);
|
||||
|
||||
GPIO_InitTypeDef sda_gpio_init;
|
||||
sda_gpio_init = i2c_adapter->cfg->sda.init;
|
||||
sda_gpio_init.GPIO_Mode = GPIO_Mode_OUT;
|
||||
GPIO_SetBits(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin);
|
||||
GPIO_Init(i2c_adapter->cfg->sda.gpio, &sda_gpio_init);
|
||||
|
||||
/* Check SDA line to determine if slave is asserting bus and clock out if so, this may */
|
||||
/* have to be repeated (due to further bus errors) but better than clocking 0xFF into an */
|
||||
/* ESC */
|
||||
|
||||
retry_count_clk = 0;
|
||||
while (GPIO_ReadInputDataBit(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin) == Bit_RESET && (retry_count_clk++ < MAX_I2C_RETRY_COUNT)) {
|
||||
retry_count = 0;
|
||||
/* Set clock high and wait for any clock stretching to finish. */
|
||||
GPIO_SetBits(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin);
|
||||
while (GPIO_ReadInputDataBit(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin) == Bit_RESET && (retry_count++ < MAX_I2C_RETRY_COUNT)) {
|
||||
PIOS_DELAY_WaituS(1);
|
||||
}
|
||||
|
||||
PIOS_DELAY_WaituS(2);
|
||||
|
||||
/* Set clock low */
|
||||
GPIO_ResetBits(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin);
|
||||
PIOS_DELAY_WaituS(2);
|
||||
|
||||
/* Clock high again */
|
||||
GPIO_SetBits(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin);
|
||||
PIOS_DELAY_WaituS(2);
|
||||
}
|
||||
|
||||
/* Generate a start then stop condition */
|
||||
GPIO_SetBits(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin);
|
||||
PIOS_DELAY_WaituS(2);
|
||||
GPIO_ResetBits(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin);
|
||||
PIOS_DELAY_WaituS(2);
|
||||
GPIO_ResetBits(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin);
|
||||
PIOS_DELAY_WaituS(2);
|
||||
|
||||
/* Set data and clock high and wait for any clock stretching to finish. */
|
||||
GPIO_SetBits(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin);
|
||||
GPIO_SetBits(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin);
|
||||
|
||||
retry_count = 0;
|
||||
while (GPIO_ReadInputDataBit(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin) == Bit_RESET && (retry_count++ < MAX_I2C_RETRY_COUNT)) {
|
||||
PIOS_DELAY_WaituS(1);
|
||||
}
|
||||
|
||||
/* Wait for data to be high */
|
||||
retry_count = 0;
|
||||
while (GPIO_ReadInputDataBit(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin) != Bit_SET && (retry_count++ < MAX_I2C_RETRY_COUNT)) {
|
||||
PIOS_DELAY_WaituS(1);
|
||||
}
|
||||
|
||||
/* Bus signals are guaranteed to be high (ie. free) after this point */
|
||||
/* Initialize the GPIO pins to the peripheral function */
|
||||
if (i2c_adapter->cfg->remapSCL) {
|
||||
GPIO_PinAFConfig(i2c_adapter->cfg->scl.gpio,
|
||||
__builtin_ctz(i2c_adapter->cfg->scl.init.GPIO_Pin),
|
||||
i2c_adapter->cfg->remapSCL);
|
||||
}
|
||||
if (i2c_adapter->cfg->remapSDA) {
|
||||
GPIO_PinAFConfig(i2c_adapter->cfg->sda.gpio,
|
||||
__builtin_ctz(i2c_adapter->cfg->sda.init.GPIO_Pin),
|
||||
i2c_adapter->cfg->remapSDA);
|
||||
}
|
||||
GPIO_Init(i2c_adapter->cfg->scl.gpio, (GPIO_InitTypeDef *)&(i2c_adapter->cfg->scl.init)); // Struct is const, function signature not
|
||||
GPIO_Init(i2c_adapter->cfg->sda.gpio, (GPIO_InitTypeDef *)&(i2c_adapter->cfg->sda.init));
|
||||
|
||||
RCC_I2CCLKConfig(i2c_adapter->cfg->regs == I2C2 ? RCC_I2C2CLK_SYSCLK : RCC_I2C1CLK_SYSCLK);
|
||||
|
||||
/* Reset the I2C block */
|
||||
I2C_DeInit(i2c_adapter->cfg->regs);
|
||||
|
||||
/* Initialize the I2C block */
|
||||
I2C_Init(i2c_adapter->cfg->regs, (I2C_InitTypeDef *)&(i2c_adapter->cfg->init));
|
||||
|
||||
/* Enable the I2C block */
|
||||
I2C_Cmd(i2c_adapter->cfg->regs, ENABLE);
|
||||
|
||||
if (I2C_GetFlagStatus(i2c_adapter->cfg->regs, I2C_FLAG_BUSY)) {
|
||||
I2C_SoftwareResetCmd(i2c_adapter->cfg->regs);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Logs the last N state transitions and N IRQ events due to
|
||||
* an error condition
|
||||
* \param[in] i2c the adapter number to log an event for
|
||||
*/
|
||||
#if defined(PIOS_I2C_DIAGNOSTICS)
|
||||
void i2c_adapter_log_fault(__attribute__((unused)) struct pios_i2c_adapter *i2c_adapter, enum pios_i2c_error_type type)
|
||||
{
|
||||
i2c_adapter_fault_history.type = type;
|
||||
for (uint8_t i = 0; i < I2C_LOG_DEPTH; i++) {
|
||||
i2c_adapter_fault_history.evirq[i] =
|
||||
i2c_evirq_history[(I2C_LOG_DEPTH + i2c_evirq_history_pointer - 1 - i) % I2C_LOG_DEPTH];
|
||||
i2c_adapter_fault_history.erirq[i] =
|
||||
i2c_erirq_history[(I2C_LOG_DEPTH + i2c_erirq_history_pointer - 1 - i) % I2C_LOG_DEPTH];
|
||||
i2c_adapter_fault_history.event[i] =
|
||||
i2c_state_event_history[(I2C_LOG_DEPTH + i2c_state_event_history_pointer - 1 - i) % I2C_LOG_DEPTH];
|
||||
i2c_adapter_fault_history.state[i] =
|
||||
i2c_state_history[(I2C_LOG_DEPTH + i2c_state_history_pointer - 1 - i) % I2C_LOG_DEPTH];
|
||||
}
|
||||
switch (type) {
|
||||
case PIOS_I2C_ERROR_EVENT:
|
||||
i2c_bad_event_counter++;
|
||||
break;
|
||||
case PIOS_I2C_ERROR_FSM:
|
||||
i2c_fsm_fault_count++;
|
||||
break;
|
||||
case PIOS_I2C_ERROR_INTERRUPT:
|
||||
i2c_error_interrupt_counter++;
|
||||
break;
|
||||
}
|
||||
}
|
||||
#endif /* if defined(PIOS_I2C_DIAGNOSTICS) */
|
||||
|
||||
/**
|
||||
* Logs the last N state transitions and N IRQ events due to
|
||||
* an error condition
|
||||
* \param[out] data address where to copy the pios_i2c_fault_history structure to
|
||||
* \param[out] counts three uint16 that receive the bad event, fsm, and error irq
|
||||
* counts
|
||||
*/
|
||||
void PIOS_I2C_GetDiagnostics(struct pios_i2c_fault_history *data, uint8_t *counts)
|
||||
{
|
||||
#if defined(PIOS_I2C_DIAGNOSTICS)
|
||||
memcpy(data, &i2c_adapter_fault_history, sizeof(i2c_adapter_fault_history));
|
||||
counts[PIOS_I2C_BAD_EVENT_COUNTER] = i2c_bad_event_counter;
|
||||
counts[PIOS_I2C_FSM_FAULT_COUNT] = i2c_fsm_fault_count;
|
||||
counts[PIOS_I2C_ERROR_INTERRUPT_COUNTER] = i2c_error_interrupt_counter;
|
||||
counts[PIOS_I2C_NACK_COUNTER] = i2c_nack_counter;
|
||||
counts[PIOS_I2C_TIMEOUT_COUNTER] = i2c_timeout_counter;
|
||||
#else
|
||||
struct pios_i2c_fault_history i2c_adapter_fault_history;
|
||||
i2c_adapter_fault_history.type = PIOS_I2C_ERROR_EVENT;
|
||||
|
||||
memcpy(data, &i2c_adapter_fault_history, sizeof(i2c_adapter_fault_history));
|
||||
memset(counts, 0, sizeof(*counts) * PIOS_I2C_ERROR_COUNT_NUMELEM);
|
||||
#endif
|
||||
}
|
||||
|
||||
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)
|
||||
{
|
||||
struct pios_i2c_dev *i2c_adapter;
|
||||
|
||||
i2c_adapter = (struct pios_i2c_adapter *)PIOS_malloc(sizeof(*i2c_adapter));
|
||||
if (!i2c_adapter) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
i2c_adapter->magic = PIOS_I2C_DEV_MAGIC;
|
||||
return i2c_adapter;
|
||||
}
|
||||
#else
|
||||
static struct pios_i2c_adapter pios_i2c_adapters[PIOS_I2C_MAX_DEVS];
|
||||
static uint8_t pios_i2c_num_adapters;
|
||||
static struct pios_i2c_adapter *PIOS_I2C_alloc(void)
|
||||
{
|
||||
struct pios_i2c_adapter *i2c_adapter;
|
||||
|
||||
if (pios_i2c_num_adapters >= PIOS_I2C_MAX_DEVS) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
i2c_adapter = &pios_i2c_adapters[pios_i2c_num_adapters++];
|
||||
i2c_adapter->magic = PIOS_I2C_DEV_MAGIC;
|
||||
|
||||
return i2c_adapter;
|
||||
}
|
||||
#endif /* if defined(PIOS_INCLUDE_CHIBIOS) && 0 */
|
||||
|
||||
|
||||
/**
|
||||
* Initializes IIC driver
|
||||
* \param[in] mode currently only mode 0 supported
|
||||
* \return < 0 if initialisation failed
|
||||
*/
|
||||
int32_t PIOS_I2C_Init(uint32_t *i2c_id, const struct pios_i2c_adapter_cfg *cfg)
|
||||
{
|
||||
PIOS_DEBUG_Assert(i2c_id);
|
||||
PIOS_DEBUG_Assert(cfg);
|
||||
|
||||
struct pios_i2c_adapter *i2c_adapter;
|
||||
|
||||
i2c_adapter = (struct pios_i2c_adapter *)PIOS_I2C_alloc();
|
||||
if (!i2c_adapter) {
|
||||
goto out_fail;
|
||||
}
|
||||
|
||||
/* Bind the configuration to the device instance */
|
||||
i2c_adapter->cfg = cfg;
|
||||
|
||||
vSemaphoreCreateBinary(i2c_adapter->sem_ready);
|
||||
i2c_adapter->sem_busy = xSemaphoreCreateMutex();
|
||||
|
||||
/* Initialize the state machine */
|
||||
i2c_adapter_fsm_init(i2c_adapter);
|
||||
|
||||
*i2c_id = (uint32_t)i2c_adapter;
|
||||
|
||||
/* Configure and enable I2C interrupts */
|
||||
NVIC_Init((NVIC_InitTypeDef *)&(i2c_adapter->cfg->event.init));
|
||||
NVIC_Init((NVIC_InitTypeDef *)&(i2c_adapter->cfg->error.init));
|
||||
|
||||
/* No error */
|
||||
return 0;
|
||||
|
||||
out_fail:
|
||||
return -1;
|
||||
}
|
||||
|
||||
int32_t PIOS_I2C_Transfer(uint32_t i2c_id, const struct pios_i2c_txn txn_list[], uint32_t num_txns)
|
||||
{
|
||||
// FIXME: only supports transfer sizes up to 255 bytes
|
||||
struct pios_i2c_adapter *i2c_adapter = (struct pios_i2c_adapter *)i2c_id;
|
||||
|
||||
bool valid = PIOS_I2C_validate(i2c_adapter);
|
||||
|
||||
PIOS_Assert(valid)
|
||||
|
||||
PIOS_DEBUG_Assert(txn_list);
|
||||
PIOS_DEBUG_Assert(num_txns);
|
||||
|
||||
bool semaphore_success = true;
|
||||
|
||||
#ifdef USE_FREERTOS
|
||||
/* Lock the bus */
|
||||
portTickType timeout;
|
||||
timeout = i2c_adapter->cfg->transfer_timeout_ms / portTICK_RATE_MS;
|
||||
if (xSemaphoreTake(i2c_adapter->sem_busy, timeout) == pdFALSE) {
|
||||
return -2;
|
||||
}
|
||||
#else
|
||||
PIOS_IRQ_Disable();
|
||||
if (i2c_adapter->busy) {
|
||||
PIOS_IRQ_Enable();
|
||||
return -2;
|
||||
}
|
||||
i2c_adapter->busy = 1;
|
||||
PIOS_IRQ_Enable();
|
||||
#endif /* USE_FREERTOS */
|
||||
|
||||
PIOS_DEBUG_Assert(i2c_adapter->curr_state == I2C_STATE_STOPPED);
|
||||
|
||||
i2c_adapter->last_txn = &txn_list[num_txns - 1];
|
||||
i2c_adapter->active_txn = &txn_list[0];
|
||||
i2c_adapter->bus_error = false;
|
||||
i2c_adapter->nack = false;
|
||||
|
||||
#ifdef USE_FREERTOS
|
||||
/* Make sure the done/ready semaphore is consumed before we start */
|
||||
semaphore_success &= (xSemaphoreTake(i2c_adapter->sem_ready, timeout) == pdTRUE);
|
||||
#endif
|
||||
|
||||
i2c_adapter->callback = NULL;
|
||||
|
||||
bool dummy = false;
|
||||
i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_START, &dummy);
|
||||
|
||||
/* Wait for the transfer to complete */
|
||||
#ifdef USE_FREERTOS
|
||||
semaphore_success &= (xSemaphoreTake(i2c_adapter->sem_ready, timeout) == pdTRUE);
|
||||
xSemaphoreGive(i2c_adapter->sem_ready);
|
||||
#endif /* USE_FREERTOS */
|
||||
|
||||
#ifdef USE_FREERTOS
|
||||
/* Unlock the bus */
|
||||
xSemaphoreGive(i2c_adapter->sem_busy);
|
||||
#if defined(PIOS_I2C_DIAGNOSTICS)
|
||||
if (!semaphore_success) {
|
||||
i2c_timeout_counter++;
|
||||
}
|
||||
#endif
|
||||
#else
|
||||
PIOS_IRQ_Disable();
|
||||
i2c_adapter->busy = 0;
|
||||
PIOS_IRQ_Enable();
|
||||
#endif /* USE_FREERTOS */
|
||||
|
||||
return !semaphore_success ? -2 :
|
||||
i2c_adapter->bus_error ? -1 :
|
||||
i2c_adapter->nack ? -3 :
|
||||
0;
|
||||
}
|
||||
|
||||
static int32_t PIOS_I2C_Transfer_Callback_Internal(struct pios_i2c_adapter *i2c_adapter, const struct pios_i2c_txn txn_list[], uint32_t num_txns, pios_i2c_callback callback)
|
||||
{
|
||||
PIOS_DEBUG_Assert(i2c_adapter->curr_state == I2C_STATE_STOPPED);
|
||||
|
||||
i2c_adapter->last_txn = &txn_list[num_txns - 1];
|
||||
i2c_adapter->active_txn = &txn_list[0];
|
||||
i2c_adapter->bus_error = false;
|
||||
i2c_adapter->nack = false;
|
||||
i2c_adapter->callback = callback;
|
||||
|
||||
// Estimate bytes of transmission. Per txns: 1 adress byte + length
|
||||
i2c_adapter->transfer_timeout_ticks = num_txns;
|
||||
for (uint32_t i = 0; i < num_txns; i++) {
|
||||
i2c_adapter->transfer_timeout_ticks += txn_list[i].len;
|
||||
}
|
||||
// timeout if it takes eight times the expected time
|
||||
i2c_adapter->transfer_timeout_ticks <<= 3;
|
||||
|
||||
bool dummy = false;
|
||||
i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_START, &dummy);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int32_t PIOS_I2C_Transfer_Callback(uint32_t i2c_id, const struct pios_i2c_txn txn_list[], uint32_t num_txns, pios_i2c_callback callback)
|
||||
{
|
||||
// FIXME: only supports transfer sizes up to 255 bytes
|
||||
struct pios_i2c_adapter *i2c_adapter = (struct pios_i2c_adapter *)i2c_id;
|
||||
|
||||
bool valid = PIOS_I2C_validate(i2c_adapter);
|
||||
|
||||
PIOS_Assert(valid)
|
||||
|
||||
PIOS_DEBUG_Assert(txn_list);
|
||||
PIOS_DEBUG_Assert(num_txns);
|
||||
|
||||
#ifdef USE_FREERTOS
|
||||
/* Lock the bus */
|
||||
portTickType timeout;
|
||||
timeout = i2c_adapter->cfg->transfer_timeout_ms / portTICK_RATE_MS;
|
||||
if (xSemaphoreTake(i2c_adapter->sem_busy, timeout) == pdFALSE) {
|
||||
return -2;
|
||||
}
|
||||
#else
|
||||
PIOS_IRQ_Disable();
|
||||
if (i2c_adapter->busy) {
|
||||
PIOS_IRQ_Enable();
|
||||
return -2;
|
||||
}
|
||||
i2c_adapter->busy = 1;
|
||||
PIOS_IRQ_Enable();
|
||||
#endif /* USE_FREERTOS */
|
||||
|
||||
return PIOS_I2C_Transfer_Callback_Internal(i2c_adapter, txn_list, num_txns, callback);
|
||||
}
|
||||
|
||||
int32_t PIOS_I2C_Transfer_CallbackFromISR(uint32_t i2c_id, const struct pios_i2c_txn txn_list[], uint32_t num_txns, pios_i2c_callback callback, bool *woken)
|
||||
{
|
||||
// FIXME: only supports transfer sizes up to 255 bytes
|
||||
struct pios_i2c_adapter *i2c_adapter = (struct pios_i2c_adapter *)i2c_id;
|
||||
|
||||
bool valid = PIOS_I2C_validate(i2c_adapter);
|
||||
|
||||
PIOS_Assert(valid)
|
||||
|
||||
PIOS_DEBUG_Assert(txn_list);
|
||||
PIOS_DEBUG_Assert(num_txns);
|
||||
|
||||
#ifdef USE_FREERTOS
|
||||
signed portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
|
||||
|
||||
/* Lock the bus */
|
||||
bool locked = xSemaphoreTakeFromISR(i2c_adapter->sem_busy, &xHigherPriorityTaskWoken) == pdTRUE;
|
||||
|
||||
if (xHigherPriorityTaskWoken == pdTRUE) {
|
||||
*woken = true;
|
||||
}
|
||||
|
||||
if (!locked) {
|
||||
return -2;
|
||||
}
|
||||
#else
|
||||
PIOS_IRQ_Disable();
|
||||
if (i2c_adapter->busy) {
|
||||
PIOS_IRQ_Enable();
|
||||
return -2;
|
||||
}
|
||||
i2c_adapter->busy = 1;
|
||||
PIOS_IRQ_Enable();
|
||||
#endif /* USE_FREERTOS */
|
||||
|
||||
return PIOS_I2C_Transfer_Callback_Internal(i2c_adapter, txn_list, num_txns, callback);
|
||||
}
|
||||
|
||||
|
||||
static bool i2c_adapter_callback_handler(struct pios_i2c_adapter *i2c_adapter, bool *woken)
|
||||
{
|
||||
#ifdef USE_FREERTOS
|
||||
/* Unlock the bus */
|
||||
signed portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
|
||||
xSemaphoreGiveFromISR(i2c_adapter->sem_busy, &xHigherPriorityTaskWoken);
|
||||
if (xHigherPriorityTaskWoken == pdTRUE) {
|
||||
*woken = true;
|
||||
}
|
||||
#else
|
||||
PIOS_IRQ_Disable();
|
||||
i2c_adapter->busy = 0;
|
||||
PIOS_IRQ_Enable();
|
||||
#endif /* USE_FREERTOS */
|
||||
|
||||
|
||||
// Execute user supplied function
|
||||
|
||||
if (i2c_adapter->callback()) {
|
||||
*woken = true;
|
||||
}
|
||||
|
||||
return !i2c_adapter->bus_error;
|
||||
}
|
||||
|
||||
|
||||
void PIOS_I2C_EV_IRQ_Handler(uint32_t i2c_id)
|
||||
{
|
||||
struct pios_i2c_adapter *i2c_adapter = (struct pios_i2c_adapter *)i2c_id;
|
||||
|
||||
bool valid = PIOS_I2C_validate(i2c_adapter);
|
||||
|
||||
PIOS_Assert(valid)
|
||||
|
||||
bool woken = false;
|
||||
|
||||
if (I2C_GetFlagStatus(i2c_adapter->cfg->regs, I2C_FLAG_RXNE)) {
|
||||
// flag will be cleared by event
|
||||
#if defined(PIOS_I2C_DIAGNOSTICS)
|
||||
i2c_evirq_history[i2c_evirq_history_pointer] = I2C_FLAG_RXNE;
|
||||
i2c_evirq_history_pointer = (i2c_evirq_history_pointer + 1) % I2C_LOG_DEPTH;
|
||||
#endif
|
||||
i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_RECEIVER_BUFFER_NOT_EMPTY, &woken);
|
||||
} else if (I2C_GetFlagStatus(i2c_adapter->cfg->regs, I2C_FLAG_TXIS)) {
|
||||
// flag will be cleared by event
|
||||
#if defined(PIOS_I2C_DIAGNOSTICS)
|
||||
i2c_evirq_history[i2c_evirq_history_pointer] = I2C_FLAG_TXIS;
|
||||
i2c_evirq_history_pointer = (i2c_evirq_history_pointer + 1) % I2C_LOG_DEPTH;
|
||||
#endif
|
||||
i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_TRANSMIT_BUFFER_EMPTY, &woken);
|
||||
} else if (I2C_GetFlagStatus(i2c_adapter->cfg->regs, I2C_FLAG_NACKF)) {
|
||||
I2C_ClearFlag(i2c_adapter->cfg->regs, I2C_FLAG_NACKF);
|
||||
#if defined(PIOS_I2C_DIAGNOSTICS)
|
||||
i2c_evirq_history[i2c_evirq_history_pointer] = I2C_FLAG_NACKF;
|
||||
i2c_evirq_history_pointer = (i2c_evirq_history_pointer + 1) % I2C_LOG_DEPTH;
|
||||
++i2c_nack_counter;
|
||||
#endif
|
||||
i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_NACK, &woken);
|
||||
} else if (I2C_GetFlagStatus(i2c_adapter->cfg->regs, I2C_FLAG_TC)) {
|
||||
I2C_ClearFlag(i2c_adapter->cfg->regs, I2C_FLAG_TC);
|
||||
#if defined(PIOS_I2C_DIAGNOSTICS)
|
||||
i2c_evirq_history[i2c_evirq_history_pointer] = I2C_FLAG_TC;
|
||||
i2c_evirq_history_pointer = (i2c_evirq_history_pointer + 1) % I2C_LOG_DEPTH;
|
||||
#endif
|
||||
i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_TRANSFER_COMPLETE, &woken);
|
||||
} else if (I2C_GetFlagStatus(i2c_adapter->cfg->regs, I2C_FLAG_STOPF)) {
|
||||
I2C_ClearFlag(i2c_adapter->cfg->regs, I2C_FLAG_STOPF);
|
||||
#if defined(PIOS_I2C_DIAGNOSTICS)
|
||||
i2c_evirq_history[i2c_evirq_history_pointer] = I2C_FLAG_STOPF;
|
||||
i2c_evirq_history_pointer = (i2c_evirq_history_pointer + 1) % I2C_LOG_DEPTH;
|
||||
#endif
|
||||
i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_STOP, &woken);
|
||||
}
|
||||
|
||||
portEND_SWITCHING_ISR(woken ? pdTRUE : pdFALSE);
|
||||
}
|
||||
|
||||
|
||||
void PIOS_I2C_ER_IRQ_Handler(uint32_t i2c_id)
|
||||
{
|
||||
struct pios_i2c_adapter *i2c_adapter = (struct pios_i2c_adapter *)i2c_id;
|
||||
|
||||
bool valid = PIOS_I2C_validate(i2c_adapter);
|
||||
|
||||
PIOS_Assert(valid)
|
||||
|
||||
else if (I2C_GetFlagStatus(i2c_adapter->cfg->regs, I2C_FLAG_BERR)) {
|
||||
I2C_ClearFlag(i2c_adapter->cfg->regs, I2C_FLAG_BERR);
|
||||
#if defined(PIOS_I2C_DIAGNOSTICS)
|
||||
i2c_erirq_history[i2c_erirq_history_pointer] = I2C_FLAG_BERR;
|
||||
i2c_erirq_history_pointer = (i2c_erirq_history_pointer + 1) % I2C_LOG_DEPTH;
|
||||
#endif
|
||||
} else if (I2C_GetFlagStatus(i2c_adapter->cfg->regs, I2C_FLAG_ARLO)) {
|
||||
I2C_ClearFlag(i2c_adapter->cfg->regs, I2C_FLAG_ARLO);
|
||||
#if defined(PIOS_I2C_DIAGNOSTICS)
|
||||
i2c_erirq_history[i2c_erirq_history_pointer] = I2C_FLAG_ARLO;
|
||||
i2c_erirq_history_pointer = (i2c_erirq_history_pointer + 1) % I2C_LOG_DEPTH;
|
||||
#endif
|
||||
} else if (I2C_GetFlagStatus(i2c_adapter->cfg->regs, I2C_FLAG_OVR)) {
|
||||
I2C_ClearFlag(i2c_adapter->cfg->regs, I2C_FLAG_OVR);
|
||||
#if defined(PIOS_I2C_DIAGNOSTICS)
|
||||
i2c_erirq_history[i2c_erirq_history_pointer] = I2C_FLAG_OVR;
|
||||
i2c_erirq_history_pointer = (i2c_erirq_history_pointer + 1) % I2C_LOG_DEPTH;
|
||||
#endif
|
||||
} else if (I2C_GetFlagStatus(i2c_adapter->cfg->regs, I2C_FLAG_PECERR)) {
|
||||
I2C_ClearFlag(i2c_adapter->cfg->regs, I2C_FLAG_PECERR);
|
||||
#if defined(PIOS_I2C_DIAGNOSTICS)
|
||||
i2c_erirq_history[i2c_erirq_history_pointer] = I2C_FLAG_PECERR;
|
||||
i2c_erirq_history_pointer = (i2c_erirq_history_pointer + 1) % I2C_LOG_DEPTH;
|
||||
#endif
|
||||
} else if (I2C_GetFlagStatus(i2c_adapter->cfg->regs, I2C_FLAG_TIMEOUT)) {
|
||||
I2C_ClearFlag(i2c_adapter->cfg->regs, I2C_FLAG_TIMEOUT);
|
||||
#if defined(PIOS_I2C_DIAGNOSTICS)
|
||||
i2c_erirq_history[i2c_erirq_history_pointer] = I2C_FLAG_TIMEOUT;
|
||||
i2c_erirq_history_pointer = (i2c_erirq_history_pointer + 1) % I2C_LOG_DEPTH;
|
||||
#endif
|
||||
} else if (I2C_GetFlagStatus(i2c_adapter->cfg->regs, I2C_FLAG_ALERT)) {
|
||||
I2C_ClearFlag(i2c_adapter->cfg->regs, I2C_FLAG_ALERT);
|
||||
#if defined(PIOS_I2C_DIAGNOSTICS)
|
||||
i2c_erirq_history[i2c_erirq_history_pointer] = I2C_FLAG_ALERT;
|
||||
i2c_erirq_history_pointer = (i2c_erirq_history_pointer + 1) % I2C_LOG_DEPTH;
|
||||
#endif
|
||||
} else if (I2C_GetFlagStatus(i2c_adapter->cfg->regs, I2C_FLAG_BUSY)) {
|
||||
I2C_ClearFlag(i2c_adapter->cfg->regs, I2C_FLAG_BUSY);
|
||||
#if defined(PIOS_I2C_DIAGNOSTICS)
|
||||
i2c_erirq_history[i2c_erirq_history_pointer] = I2C_FLAG_BUSY;
|
||||
i2c_erirq_history_pointer = (i2c_erirq_history_pointer + 1) % I2C_LOG_DEPTH;
|
||||
#endif
|
||||
}
|
||||
|
||||
#if defined(PIOS_I2C_DIAGNOSTICS)
|
||||
i2c_adapter_log_fault(i2c_adapter, PIOS_I2C_ERROR_INTERRUPT);
|
||||
#endif
|
||||
|
||||
/* Fail hard on any errors for now */
|
||||
bool woken = false;
|
||||
i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_BUS_ERROR, &woken);
|
||||
|
||||
portEND_SWITCHING_ISR(woken ? pdTRUE : pdFALSE);
|
||||
}
|
||||
|
||||
#endif /* if defined(PIOS_INCLUDE_I2C) */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
97
flight/pios/stm32f30x/pios_irq.c
Normal file
97
flight/pios/stm32f30x/pios_irq.c
Normal file
@ -0,0 +1,97 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_IRQ IRQ Setup Functions
|
||||
* @brief STM32 Hardware code to enable and disable interrupts
|
||||
* @{
|
||||
*
|
||||
* @file pios_irq.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org)
|
||||
* @brief IRQ Enable/Disable routines
|
||||
* @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_IRQ
|
||||
|
||||
/* Private Function Prototypes */
|
||||
|
||||
/* Local Variables */
|
||||
/* The nesting counter ensures, that interrupts won't be enabled so long nested functions disable them */
|
||||
static uint32_t nested_ctr;
|
||||
|
||||
/* Stored priority level before IRQ has been disabled (important for co-existence with vPortEnterCritical) */
|
||||
static uint32_t prev_primask;
|
||||
|
||||
/**
|
||||
* Disables all interrupts (nested)
|
||||
* \return < 0 On errors
|
||||
*/
|
||||
int32_t PIOS_IRQ_Disable(void)
|
||||
{
|
||||
/* Get current priority if nested level == 0 */
|
||||
if (!nested_ctr) {
|
||||
__asm volatile (" mrs %0, primask\n" : "=r" (prev_primask)
|
||||
);
|
||||
}
|
||||
|
||||
/* Disable interrupts */
|
||||
__asm volatile (" mov r0, #1 \n" " msr primask, r0\n" ::: "r0");
|
||||
|
||||
++nested_ctr;
|
||||
|
||||
/* No error */
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Enables all interrupts (nested)
|
||||
* \return < 0 on errors
|
||||
* \return -1 on nesting errors (PIOS_IRQ_Disable() hasn't been called before)
|
||||
*/
|
||||
int32_t PIOS_IRQ_Enable(void)
|
||||
{
|
||||
/* Check for nesting error */
|
||||
if (nested_ctr == 0) {
|
||||
/* Nesting error */
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* Decrease nesting level */
|
||||
--nested_ctr;
|
||||
|
||||
/* Set back previous priority once nested level reached 0 again */
|
||||
if (nested_ctr == 0) {
|
||||
__asm volatile (" msr primask, %0\n" ::"r" (prev_primask)
|
||||
);
|
||||
}
|
||||
|
||||
/* No error */
|
||||
return 0;
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_IRQ */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
401
flight/pios/stm32f30x/pios_ppm.c
Normal file
401
flight/pios/stm32f30x/pios_ppm.c
Normal file
@ -0,0 +1,401 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_PPM PPM Input Functions
|
||||
* @brief Code to measure PPM input and seperate into channels
|
||||
* @{
|
||||
*
|
||||
* @file pios_ppm.c
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016.
|
||||
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief PPM Input functions (STM32 dependent)
|
||||
* @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_PPM
|
||||
|
||||
#include "pios_ppm_priv.h"
|
||||
|
||||
/* Provide a RCVR driver */
|
||||
static int32_t PIOS_PPM_Get(uint32_t rcvr_id, uint8_t channel);
|
||||
static xSemaphoreHandle PIOS_PPM_Get_Semaphore(uint32_t rcvr_id, uint8_t channel);
|
||||
|
||||
const struct pios_rcvr_driver pios_ppm_rcvr_driver = {
|
||||
.read = PIOS_PPM_Get,
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
.get_semaphore = PIOS_PPM_Get_Semaphore
|
||||
#endif
|
||||
};
|
||||
|
||||
#define PIOS_PPM_IN_MIN_NUM_CHANNELS 4
|
||||
#define PIOS_PPM_IN_MAX_NUM_CHANNELS PIOS_PPM_NUM_INPUTS
|
||||
#define PIOS_PPM_STABLE_CHANNEL_COUNT 25 // frames
|
||||
#define PIOS_PPM_IN_MIN_SYNC_PULSE_US 2700 // microseconds
|
||||
#define PIOS_PPM_IN_MIN_CHANNEL_PULSE_US 750 // microseconds
|
||||
#define PIOS_PPM_IN_MAX_CHANNEL_PULSE_US 2250 // microseconds
|
||||
|
||||
static void PIOS_PPM_Supervisor(uint32_t ppm_id);
|
||||
|
||||
enum pios_ppm_dev_magic {
|
||||
PIOS_PPM_DEV_MAGIC = 0xee014d8b,
|
||||
};
|
||||
|
||||
struct pios_ppm_dev {
|
||||
enum pios_ppm_dev_magic magic;
|
||||
const struct pios_ppm_cfg *cfg;
|
||||
|
||||
uint8_t PulseIndex;
|
||||
uint32_t PreviousTime;
|
||||
uint32_t CurrentTime;
|
||||
uint32_t DeltaTime;
|
||||
uint32_t CaptureValue[PIOS_PPM_IN_MAX_NUM_CHANNELS];
|
||||
uint32_t CaptureValueNewFrame[PIOS_PPM_IN_MAX_NUM_CHANNELS];
|
||||
uint32_t LargeCounter;
|
||||
int8_t NumChannels;
|
||||
int8_t NumChannelsPrevFrame;
|
||||
uint8_t NumChannelCounter;
|
||||
|
||||
uint8_t supv_timer;
|
||||
bool Tracking;
|
||||
bool Fresh;
|
||||
|
||||
#ifdef PIOS_INCLUDE_FREERTOS
|
||||
xSemaphoreHandle new_sample_semaphores[PIOS_PPM_IN_MIN_NUM_CHANNELS];
|
||||
#endif /* PIOS_INCLUDE_FREERTOS */
|
||||
};
|
||||
|
||||
static bool PIOS_PPM_validate(struct pios_ppm_dev *ppm_dev)
|
||||
{
|
||||
return ppm_dev->magic == PIOS_PPM_DEV_MAGIC;
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
static struct pios_ppm_dev *PIOS_PPM_alloc(void)
|
||||
{
|
||||
struct pios_ppm_dev *ppm_dev;
|
||||
|
||||
ppm_dev = (struct pios_ppm_dev *)pios_malloc(sizeof(*ppm_dev));
|
||||
if (!ppm_dev) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
// Initialize the semaphores to 0.
|
||||
for (uint8_t i = 0; i < PIOS_PPM_IN_MIN_NUM_CHANNELS; ++i) {
|
||||
ppm_dev->new_sample_semaphores[i] = 0;
|
||||
}
|
||||
|
||||
ppm_dev->magic = PIOS_PPM_DEV_MAGIC;
|
||||
return ppm_dev;
|
||||
}
|
||||
#else
|
||||
static struct pios_ppm_dev pios_ppm_devs[PIOS_PPM_MAX_DEVS];
|
||||
static uint8_t pios_ppm_num_devs;
|
||||
static struct pios_ppm_dev *PIOS_PPM_alloc(void)
|
||||
{
|
||||
struct pios_ppm_dev *ppm_dev;
|
||||
|
||||
if (pios_ppm_num_devs >= PIOS_PPM_MAX_DEVS) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
ppm_dev = &pios_ppm_devs[pios_ppm_num_devs++];
|
||||
ppm_dev->magic = PIOS_PPM_DEV_MAGIC;
|
||||
|
||||
return ppm_dev;
|
||||
}
|
||||
#endif /* if defined(PIOS_INCLUDE_FREERTOS) */
|
||||
|
||||
static void PIOS_PPM_tim_overflow_cb(uint32_t id, uint32_t context, uint8_t channel, uint16_t count);
|
||||
static void PIOS_PPM_tim_edge_cb(uint32_t id, uint32_t context, uint8_t channel, uint16_t count);
|
||||
static const struct pios_tim_callbacks tim_callbacks = {
|
||||
.overflow = PIOS_PPM_tim_overflow_cb,
|
||||
.edge = PIOS_PPM_tim_edge_cb,
|
||||
};
|
||||
|
||||
extern int32_t PIOS_PPM_Init(uint32_t *ppm_id, const struct pios_ppm_cfg *cfg)
|
||||
{
|
||||
PIOS_DEBUG_Assert(ppm_id);
|
||||
PIOS_DEBUG_Assert(cfg);
|
||||
|
||||
struct pios_ppm_dev *ppm_dev;
|
||||
|
||||
ppm_dev = (struct pios_ppm_dev *)PIOS_PPM_alloc();
|
||||
if (!ppm_dev) {
|
||||
goto out_fail;
|
||||
}
|
||||
|
||||
/* Bind the configuration to the device instance */
|
||||
ppm_dev->cfg = cfg;
|
||||
|
||||
/* Set up the state variables */
|
||||
ppm_dev->PulseIndex = 0;
|
||||
ppm_dev->PreviousTime = 0;
|
||||
ppm_dev->CurrentTime = 0;
|
||||
ppm_dev->DeltaTime = 0;
|
||||
ppm_dev->LargeCounter = 0;
|
||||
ppm_dev->NumChannels = -1;
|
||||
ppm_dev->NumChannelsPrevFrame = -1;
|
||||
ppm_dev->NumChannelCounter = 0;
|
||||
ppm_dev->Tracking = false;
|
||||
ppm_dev->Fresh = false;
|
||||
|
||||
for (uint8_t i = 0; i < PIOS_PPM_IN_MAX_NUM_CHANNELS; i++) {
|
||||
/* Flush counter variables */
|
||||
ppm_dev->CaptureValue[i] = PIOS_RCVR_TIMEOUT;
|
||||
ppm_dev->CaptureValueNewFrame[i] = PIOS_RCVR_TIMEOUT;
|
||||
}
|
||||
|
||||
uint32_t tim_id;
|
||||
if (PIOS_TIM_InitChannels(&tim_id, cfg->channels, cfg->num_channels, &tim_callbacks, (uint32_t)ppm_dev)) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
TIM_ICInitTypeDef TIM_ICInitStructure = cfg->tim_ic_init;
|
||||
|
||||
/* Configure the channels to be in capture/compare mode */
|
||||
for (uint8_t i = 0; i < cfg->num_channels; i++) {
|
||||
const struct pios_tim_channel *chan = &cfg->channels[i];
|
||||
|
||||
/* Configure timer for input capture */
|
||||
TIM_ICInitStructure.TIM_Channel = chan->timer_chan;
|
||||
TIM_ICInit(chan->timer, &TIM_ICInitStructure);
|
||||
|
||||
/* Enable the Capture Compare Interrupt Request */
|
||||
switch (chan->timer_chan) {
|
||||
case TIM_Channel_1:
|
||||
TIM_ITConfig(chan->timer, TIM_IT_CC1 | TIM_IT_Update, ENABLE);
|
||||
break;
|
||||
case TIM_Channel_2:
|
||||
TIM_ITConfig(chan->timer, TIM_IT_CC2 | TIM_IT_Update, ENABLE);
|
||||
break;
|
||||
case TIM_Channel_3:
|
||||
TIM_ITConfig(chan->timer, TIM_IT_CC3 | TIM_IT_Update, ENABLE);
|
||||
break;
|
||||
case TIM_Channel_4:
|
||||
TIM_ITConfig(chan->timer, TIM_IT_CC4 | TIM_IT_Update, ENABLE);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
if (!PIOS_RTC_RegisterTickCallback(PIOS_PPM_Supervisor, (uint32_t)ppm_dev)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
|
||||
*ppm_id = (uint32_t)ppm_dev;
|
||||
|
||||
return 0;
|
||||
|
||||
out_fail:
|
||||
return -1;
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
static xSemaphoreHandle PIOS_PPM_Get_Semaphore(uint32_t rcvr_id, uint8_t channel)
|
||||
{
|
||||
struct pios_ppm_dev *ppm_dev = (struct pios_ppm_dev *)rcvr_id;
|
||||
|
||||
if (!PIOS_PPM_validate(ppm_dev)) {
|
||||
/* Invalid device specified */
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (channel >= PIOS_PPM_IN_MAX_NUM_CHANNELS) {
|
||||
/* Channel out of range */
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (ppm_dev->new_sample_semaphores[channel] == 0) {
|
||||
vSemaphoreCreateBinary(ppm_dev->new_sample_semaphores[channel]);
|
||||
}
|
||||
return ppm_dev->new_sample_semaphores[channel];
|
||||
}
|
||||
#endif /* if defined(PIOS_INCLUDE_FREERTOS) */
|
||||
|
||||
/**
|
||||
* Get the value of an input channel
|
||||
* \param[in] channel Number of the channel desired (zero based)
|
||||
* \output PIOS_RCVR_INVALID channel not available
|
||||
* \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver
|
||||
* \output >=0 channel value
|
||||
*/
|
||||
static int32_t PIOS_PPM_Get(uint32_t rcvr_id, uint8_t channel)
|
||||
{
|
||||
struct pios_ppm_dev *ppm_dev = (struct pios_ppm_dev *)rcvr_id;
|
||||
|
||||
if (!PIOS_PPM_validate(ppm_dev)) {
|
||||
/* Invalid device specified */
|
||||
return PIOS_RCVR_INVALID;
|
||||
}
|
||||
|
||||
if (channel >= PIOS_PPM_IN_MAX_NUM_CHANNELS) {
|
||||
/* Channel out of range */
|
||||
return PIOS_RCVR_INVALID;
|
||||
}
|
||||
return ppm_dev->CaptureValue[channel];
|
||||
}
|
||||
|
||||
static void PIOS_PPM_tim_overflow_cb(__attribute__((unused)) uint32_t tim_id, uint32_t context,
|
||||
__attribute__((unused)) uint8_t channel, uint16_t count)
|
||||
{
|
||||
struct pios_ppm_dev *ppm_dev = (struct pios_ppm_dev *)context;
|
||||
|
||||
if (!PIOS_PPM_validate(ppm_dev)) {
|
||||
/* Invalid device specified */
|
||||
return;
|
||||
}
|
||||
|
||||
ppm_dev->LargeCounter += count;
|
||||
}
|
||||
|
||||
|
||||
static void PIOS_PPM_tim_edge_cb(__attribute__((unused)) uint32_t tim_id, uint32_t context, uint8_t chan_idx, uint16_t count)
|
||||
{
|
||||
/* Recover our device context */
|
||||
struct pios_ppm_dev *ppm_dev = (struct pios_ppm_dev *)context;
|
||||
|
||||
if (!PIOS_PPM_validate(ppm_dev)) {
|
||||
/* Invalid device specified */
|
||||
return;
|
||||
}
|
||||
|
||||
if (chan_idx >= ppm_dev->cfg->num_channels) {
|
||||
/* Channel out of range */
|
||||
return;
|
||||
}
|
||||
|
||||
/* Shift the last measurement out */
|
||||
ppm_dev->PreviousTime = ppm_dev->CurrentTime;
|
||||
|
||||
/* Grab the new count */
|
||||
ppm_dev->CurrentTime = count;
|
||||
|
||||
/* Convert to 32-bit timer result */
|
||||
ppm_dev->CurrentTime += ppm_dev->LargeCounter;
|
||||
|
||||
/* Capture computation */
|
||||
ppm_dev->DeltaTime = ppm_dev->CurrentTime - ppm_dev->PreviousTime;
|
||||
|
||||
ppm_dev->PreviousTime = ppm_dev->CurrentTime;
|
||||
|
||||
/* Sync pulse detection */
|
||||
if (ppm_dev->DeltaTime > PIOS_PPM_IN_MIN_SYNC_PULSE_US) {
|
||||
if (ppm_dev->PulseIndex == ppm_dev->NumChannelsPrevFrame
|
||||
&& ppm_dev->PulseIndex >= PIOS_PPM_IN_MIN_NUM_CHANNELS
|
||||
&& ppm_dev->PulseIndex <= PIOS_PPM_IN_MAX_NUM_CHANNELS) {
|
||||
/* If we see n simultaneous frames of the same
|
||||
number of channels we save it as our frame size */
|
||||
if (ppm_dev->NumChannelCounter < PIOS_PPM_STABLE_CHANNEL_COUNT) {
|
||||
ppm_dev->NumChannelCounter++;
|
||||
} else {
|
||||
ppm_dev->NumChannels = ppm_dev->PulseIndex;
|
||||
}
|
||||
} else {
|
||||
ppm_dev->NumChannelCounter = 0;
|
||||
}
|
||||
|
||||
/* Check if the last frame was well formed */
|
||||
if (ppm_dev->PulseIndex == ppm_dev->NumChannels && ppm_dev->Tracking) {
|
||||
/* The last frame was well formed */
|
||||
for (int32_t i = 0; i < ppm_dev->NumChannels; i++) {
|
||||
ppm_dev->CaptureValue[i] = ppm_dev->CaptureValueNewFrame[i];
|
||||
}
|
||||
for (uint32_t i = ppm_dev->NumChannels;
|
||||
i < PIOS_PPM_IN_MAX_NUM_CHANNELS; i++) {
|
||||
ppm_dev->CaptureValue[i] = PIOS_RCVR_TIMEOUT;
|
||||
}
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
/* Signal that a new sample is ready on this channel. */
|
||||
if (ppm_dev->new_sample_semaphores[chan_idx] != 0) {
|
||||
signed portBASE_TYPE pxHigherPriorityTaskWoken = pdFALSE;
|
||||
if (xSemaphoreGiveFromISR(ppm_dev->new_sample_semaphores[chan_idx], &pxHigherPriorityTaskWoken) == pdTRUE) {
|
||||
portEND_SWITCHING_ISR(pxHigherPriorityTaskWoken); /* FIXME: is this the right place for his? */
|
||||
}
|
||||
}
|
||||
#endif /* USE_FREERTOS */
|
||||
} else {
|
||||
for (uint32_t i = 0;
|
||||
i < PIOS_PPM_IN_MAX_NUM_CHANNELS; i++) {
|
||||
ppm_dev->CaptureValue[i] = PIOS_RCVR_TIMEOUT;
|
||||
}
|
||||
}
|
||||
|
||||
ppm_dev->Fresh = true;
|
||||
ppm_dev->Tracking = true;
|
||||
ppm_dev->NumChannelsPrevFrame = ppm_dev->PulseIndex;
|
||||
ppm_dev->PulseIndex = 0;
|
||||
|
||||
/* We rely on the supervisor to set CaptureValue to invalid
|
||||
if no valid frame is found otherwise we ride over it */
|
||||
} else if (ppm_dev->Tracking) {
|
||||
/* Valid pulse duration 0.75 to 2.5 ms*/
|
||||
if (ppm_dev->DeltaTime > PIOS_PPM_IN_MIN_CHANNEL_PULSE_US
|
||||
&& ppm_dev->DeltaTime < PIOS_PPM_IN_MAX_CHANNEL_PULSE_US
|
||||
&& ppm_dev->PulseIndex < PIOS_PPM_IN_MAX_NUM_CHANNELS) {
|
||||
ppm_dev->CaptureValueNewFrame[ppm_dev->PulseIndex] = ppm_dev->DeltaTime;
|
||||
ppm_dev->PulseIndex++;
|
||||
} else {
|
||||
/* Not a valid pulse duration */
|
||||
ppm_dev->Tracking = false;
|
||||
for (uint32_t i = 0; i < PIOS_PPM_IN_MAX_NUM_CHANNELS; i++) {
|
||||
ppm_dev->CaptureValueNewFrame[i] = PIOS_RCVR_TIMEOUT;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void PIOS_PPM_Supervisor(uint32_t ppm_id)
|
||||
{
|
||||
/* Recover our device context */
|
||||
struct pios_ppm_dev *ppm_dev = (struct pios_ppm_dev *)ppm_id;
|
||||
|
||||
if (!PIOS_PPM_validate(ppm_dev)) {
|
||||
/* Invalid device specified */
|
||||
return;
|
||||
}
|
||||
|
||||
/*
|
||||
* RTC runs at 625Hz so divide down the base rate so
|
||||
* that this loop runs at 25Hz.
|
||||
*/
|
||||
if (++(ppm_dev->supv_timer) < 25) {
|
||||
return;
|
||||
}
|
||||
ppm_dev->supv_timer = 0;
|
||||
|
||||
if (!ppm_dev->Fresh) {
|
||||
ppm_dev->Tracking = false;
|
||||
|
||||
for (int32_t i = 0; i < PIOS_PPM_IN_MAX_NUM_CHANNELS; i++) {
|
||||
ppm_dev->CaptureValue[i] = PIOS_RCVR_TIMEOUT;
|
||||
ppm_dev->CaptureValueNewFrame[i] = PIOS_RCVR_TIMEOUT;
|
||||
}
|
||||
}
|
||||
|
||||
ppm_dev->Fresh = false;
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_PPM */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
283
flight/pios/stm32f30x/pios_pwm.c
Normal file
283
flight/pios/stm32f30x/pios_pwm.c
Normal file
@ -0,0 +1,283 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_PWM PWM Input Functions
|
||||
* @brief Code to measure with PWM input
|
||||
* @{
|
||||
*
|
||||
* @file pios_pwm.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief PWM Input functions (STM32 dependent)
|
||||
* @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_PWM
|
||||
|
||||
#include "pios_pwm_priv.h"
|
||||
|
||||
/* Provide a RCVR driver */
|
||||
static int32_t PIOS_PWM_Get(uint32_t rcvr_id, uint8_t channel);
|
||||
|
||||
const struct pios_rcvr_driver pios_pwm_rcvr_driver = {
|
||||
.read = PIOS_PWM_Get,
|
||||
};
|
||||
|
||||
/* Local Variables */
|
||||
/* 100 ms timeout without updates on channels */
|
||||
static const uint32_t PWM_SUPERVISOR_TIMEOUT = 100000;
|
||||
|
||||
enum pios_pwm_dev_magic {
|
||||
PIOS_PWM_DEV_MAGIC = 0xab30293c,
|
||||
};
|
||||
|
||||
struct pios_pwm_dev {
|
||||
enum pios_pwm_dev_magic magic;
|
||||
const struct pios_pwm_cfg *cfg;
|
||||
|
||||
uint8_t CaptureState[PIOS_PWM_NUM_INPUTS];
|
||||
uint16_t RiseValue[PIOS_PWM_NUM_INPUTS];
|
||||
uint16_t FallValue[PIOS_PWM_NUM_INPUTS];
|
||||
uint32_t CaptureValue[PIOS_PWM_NUM_INPUTS];
|
||||
uint32_t CapCounter[PIOS_PWM_NUM_INPUTS];
|
||||
uint32_t us_since_update[PIOS_PWM_NUM_INPUTS];
|
||||
};
|
||||
|
||||
static bool PIOS_PWM_validate(struct pios_pwm_dev *pwm_dev)
|
||||
{
|
||||
return pwm_dev->magic == PIOS_PWM_DEV_MAGIC;
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
static struct pios_pwm_dev *PIOS_PWM_alloc(void)
|
||||
{
|
||||
struct pios_pwm_dev *pwm_dev;
|
||||
|
||||
pwm_dev = (struct pios_pwm_dev *)pios_malloc(sizeof(*pwm_dev));
|
||||
if (!pwm_dev) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
pwm_dev->magic = PIOS_PWM_DEV_MAGIC;
|
||||
return pwm_dev;
|
||||
}
|
||||
#else
|
||||
static struct pios_pwm_dev pios_pwm_devs[PIOS_PWM_MAX_DEVS];
|
||||
static uint8_t pios_pwm_num_devs;
|
||||
static struct pios_pwm_dev *PIOS_PWM_alloc(void)
|
||||
{
|
||||
struct pios_pwm_dev *pwm_dev;
|
||||
|
||||
if (pios_pwm_num_devs >= PIOS_PWM_MAX_DEVS) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
pwm_dev = &pios_pwm_devs[pios_pwm_num_devs++];
|
||||
pwm_dev->magic = PIOS_PWM_DEV_MAGIC;
|
||||
|
||||
return pwm_dev;
|
||||
}
|
||||
#endif /* if defined(PIOS_INCLUDE_FREERTOS) */
|
||||
|
||||
static void PIOS_PWM_tim_overflow_cb(uint32_t id, uint32_t context, uint8_t channel, uint16_t count);
|
||||
static void PIOS_PWM_tim_edge_cb(uint32_t id, uint32_t context, uint8_t channel, uint16_t count);
|
||||
static const struct pios_tim_callbacks tim_callbacks = {
|
||||
.overflow = PIOS_PWM_tim_overflow_cb,
|
||||
.edge = PIOS_PWM_tim_edge_cb,
|
||||
};
|
||||
|
||||
/**
|
||||
* Initialises all the pins
|
||||
*/
|
||||
int32_t PIOS_PWM_Init(uint32_t *pwm_id, const struct pios_pwm_cfg *cfg)
|
||||
{
|
||||
PIOS_DEBUG_Assert(pwm_id);
|
||||
PIOS_DEBUG_Assert(cfg);
|
||||
|
||||
struct pios_pwm_dev *pwm_dev;
|
||||
|
||||
pwm_dev = (struct pios_pwm_dev *)PIOS_PWM_alloc();
|
||||
if (!pwm_dev) {
|
||||
goto out_fail;
|
||||
}
|
||||
|
||||
/* Bind the configuration to the device instance */
|
||||
pwm_dev->cfg = cfg;
|
||||
|
||||
for (uint8_t i = 0; i < PIOS_PWM_NUM_INPUTS; i++) {
|
||||
/* Flush counter variables */
|
||||
pwm_dev->CaptureState[i] = 0;
|
||||
pwm_dev->RiseValue[i] = 0;
|
||||
pwm_dev->FallValue[i] = 0;
|
||||
pwm_dev->CaptureValue[i] = PIOS_RCVR_TIMEOUT;
|
||||
}
|
||||
|
||||
uint32_t tim_id;
|
||||
if (PIOS_TIM_InitChannels(&tim_id, cfg->channels, cfg->num_channels, &tim_callbacks, (uint32_t)pwm_dev)) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
/* Configure the channels to be in capture/compare mode */
|
||||
for (uint8_t i = 0; i < cfg->num_channels; i++) {
|
||||
const struct pios_tim_channel *chan = &cfg->channels[i];
|
||||
|
||||
/* Configure timer for input capture */
|
||||
TIM_ICInitTypeDef TIM_ICInitStructure = cfg->tim_ic_init;
|
||||
TIM_ICInitStructure.TIM_Channel = chan->timer_chan;
|
||||
TIM_ICInit(chan->timer, &TIM_ICInitStructure);
|
||||
|
||||
/* Enable the Capture Compare Interrupt Request */
|
||||
switch (chan->timer_chan) {
|
||||
case TIM_Channel_1:
|
||||
TIM_ITConfig(chan->timer, TIM_IT_CC1, ENABLE);
|
||||
break;
|
||||
case TIM_Channel_2:
|
||||
TIM_ITConfig(chan->timer, TIM_IT_CC2, ENABLE);
|
||||
break;
|
||||
case TIM_Channel_3:
|
||||
TIM_ITConfig(chan->timer, TIM_IT_CC3, ENABLE);
|
||||
break;
|
||||
case TIM_Channel_4:
|
||||
TIM_ITConfig(chan->timer, TIM_IT_CC4, ENABLE);
|
||||
break;
|
||||
}
|
||||
|
||||
// Need the update event for that timer to detect timeouts
|
||||
TIM_ITConfig(chan->timer, TIM_IT_Update, ENABLE);
|
||||
}
|
||||
|
||||
*pwm_id = (uint32_t)pwm_dev;
|
||||
|
||||
return 0;
|
||||
|
||||
out_fail:
|
||||
return -1;
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the value of an input channel
|
||||
* \param[in] channel Number of the channel desired (zero based)
|
||||
* \output PIOS_RCVR_INVALID channel not available
|
||||
* \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver
|
||||
* \output >=0 channel value
|
||||
*/
|
||||
static int32_t PIOS_PWM_Get(uint32_t rcvr_id, uint8_t channel)
|
||||
{
|
||||
struct pios_pwm_dev *pwm_dev = (struct pios_pwm_dev *)rcvr_id;
|
||||
|
||||
if (!PIOS_PWM_validate(pwm_dev)) {
|
||||
/* Invalid device specified */
|
||||
return PIOS_RCVR_INVALID;
|
||||
}
|
||||
|
||||
if (channel >= PIOS_PWM_NUM_INPUTS) {
|
||||
/* Channel out of range */
|
||||
return PIOS_RCVR_INVALID;
|
||||
}
|
||||
return pwm_dev->CaptureValue[channel];
|
||||
}
|
||||
|
||||
static void PIOS_PWM_tim_overflow_cb(__attribute__((unused)) uint32_t tim_id, uint32_t context, uint8_t channel, uint16_t count)
|
||||
{
|
||||
struct pios_pwm_dev *pwm_dev = (struct pios_pwm_dev *)context;
|
||||
|
||||
if (!PIOS_PWM_validate(pwm_dev)) {
|
||||
/* Invalid device specified */
|
||||
return;
|
||||
}
|
||||
|
||||
if (channel >= pwm_dev->cfg->num_channels) {
|
||||
/* Channel out of range */
|
||||
return;
|
||||
}
|
||||
|
||||
pwm_dev->us_since_update[channel] += count;
|
||||
if (pwm_dev->us_since_update[channel] >= PWM_SUPERVISOR_TIMEOUT) {
|
||||
pwm_dev->CaptureState[channel] = 0;
|
||||
pwm_dev->RiseValue[channel] = 0;
|
||||
pwm_dev->FallValue[channel] = 0;
|
||||
pwm_dev->CaptureValue[channel] = PIOS_RCVR_TIMEOUT;
|
||||
pwm_dev->us_since_update[channel] = 0;
|
||||
}
|
||||
}
|
||||
|
||||
static void PIOS_PWM_tim_edge_cb(__attribute__((unused)) uint32_t tim_id, uint32_t context, uint8_t chan_idx, uint16_t count)
|
||||
{
|
||||
/* Recover our device context */
|
||||
struct pios_pwm_dev *pwm_dev = (struct pios_pwm_dev *)context;
|
||||
|
||||
if (!PIOS_PWM_validate(pwm_dev)) {
|
||||
/* Invalid device specified */
|
||||
return;
|
||||
}
|
||||
|
||||
if (chan_idx >= pwm_dev->cfg->num_channels) {
|
||||
/* Channel out of range */
|
||||
return;
|
||||
}
|
||||
|
||||
const struct pios_tim_channel *chan = &pwm_dev->cfg->channels[chan_idx];
|
||||
|
||||
if (pwm_dev->CaptureState[chan_idx] == 0) {
|
||||
pwm_dev->RiseValue[chan_idx] = count;
|
||||
pwm_dev->us_since_update[chan_idx] = 0;
|
||||
} else {
|
||||
pwm_dev->FallValue[chan_idx] = count;
|
||||
}
|
||||
|
||||
// flip state machine and capture value here
|
||||
/* Simple rise or fall state machine */
|
||||
TIM_ICInitTypeDef TIM_ICInitStructure = pwm_dev->cfg->tim_ic_init;
|
||||
if (pwm_dev->CaptureState[chan_idx] == 0) {
|
||||
/* Switch states */
|
||||
pwm_dev->CaptureState[chan_idx] = 1;
|
||||
|
||||
/* Switch polarity of input capture */
|
||||
TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Falling;
|
||||
TIM_ICInitStructure.TIM_Channel = chan->timer_chan;
|
||||
TIM_ICInit(chan->timer, &TIM_ICInitStructure);
|
||||
} else {
|
||||
/* Capture computation */
|
||||
if (pwm_dev->FallValue[chan_idx] > pwm_dev->RiseValue[chan_idx]) {
|
||||
pwm_dev->CaptureValue[chan_idx] = (pwm_dev->FallValue[chan_idx] - pwm_dev->RiseValue[chan_idx]);
|
||||
} else {
|
||||
pwm_dev->CaptureValue[chan_idx] = ((chan->timer->ARR - pwm_dev->RiseValue[chan_idx]) + pwm_dev->FallValue[chan_idx]);
|
||||
}
|
||||
|
||||
/* Switch states */
|
||||
pwm_dev->CaptureState[chan_idx] = 0;
|
||||
|
||||
/* Increase supervisor counter */
|
||||
pwm_dev->CapCounter[chan_idx]++;
|
||||
|
||||
/* Switch polarity of input capture */
|
||||
TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Rising;
|
||||
TIM_ICInitStructure.TIM_Channel = chan->timer_chan;
|
||||
TIM_ICInit(chan->timer, &TIM_ICInitStructure);
|
||||
}
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_PWM */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
148
flight/pios/stm32f30x/pios_rtc.c
Normal file
148
flight/pios/stm32f30x/pios_rtc.c
Normal file
@ -0,0 +1,148 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_PWM PWM Input Functions
|
||||
* @brief Code to measure with PWM input
|
||||
* @{
|
||||
*
|
||||
* @file pios_pwm.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2013
|
||||
* @brief PWM Input functions (STM32 dependent)
|
||||
* @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
|
||||
*/
|
||||
|
||||
/* Project Includes */
|
||||
#include "pios.h"
|
||||
|
||||
#if defined(PIOS_INCLUDE_RTC)
|
||||
#include <pios_rtc_priv.h>
|
||||
|
||||
#ifndef PIOS_RTC_PRESCALER
|
||||
#define PIOS_RTC_PRESCALER 100
|
||||
#endif
|
||||
|
||||
struct rtc_callback_entry {
|
||||
void (*fn)(uint32_t);
|
||||
uint32_t data;
|
||||
};
|
||||
|
||||
#define PIOS_RTC_MAX_CALLBACKS 3
|
||||
struct rtc_callback_entry rtc_callback_list[PIOS_RTC_MAX_CALLBACKS];
|
||||
static uint8_t rtc_callback_next = 0;
|
||||
|
||||
void PIOS_RTC_Init(const struct pios_rtc_cfg *cfg)
|
||||
{
|
||||
RCC_BackupResetCmd(ENABLE);
|
||||
RCC_BackupResetCmd(DISABLE);
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR, ENABLE);
|
||||
PWR_BackupAccessCmd(ENABLE);
|
||||
// Divide external 8 MHz clock by 32 to 250kHz
|
||||
RCC_RTCCLKConfig(cfg->clksrc);
|
||||
RCC_RTCCLKCmd(ENABLE);
|
||||
|
||||
RTC_WakeUpCmd(DISABLE);
|
||||
// Divide 250kHz Mhz clock by 16 to 15625Hz
|
||||
RTC_WakeUpClockConfig(RTC_WakeUpClock_RTCCLK_Div16);
|
||||
// Divide 15625Hz by 25 to get 625 Hz
|
||||
RTC_SetWakeUpCounter(cfg->prescaler); // cfg->prescaler);
|
||||
RTC_WakeUpCmd(ENABLE);
|
||||
|
||||
/* Configure and enable the RTC Second interrupt */
|
||||
EXTI_InitTypeDef ExtiInit = {
|
||||
.EXTI_Line = EXTI_Line20, // matches above GPIO pin
|
||||
.EXTI_Mode = EXTI_Mode_Interrupt,
|
||||
.EXTI_Trigger = EXTI_Trigger_Rising,
|
||||
.EXTI_LineCmd = ENABLE,
|
||||
};
|
||||
EXTI_Init((EXTI_InitTypeDef *)&ExtiInit);
|
||||
NVIC_Init((NVIC_InitTypeDef *)&cfg->irq.init);
|
||||
RTC_ITConfig(RTC_IT_WUT, ENABLE);
|
||||
|
||||
RTC_ClearFlag(RTC_FLAG_WUTF);
|
||||
}
|
||||
|
||||
uint32_t PIOS_RTC_Counter()
|
||||
{
|
||||
return RTC_GetWakeUpCounter();
|
||||
}
|
||||
|
||||
/* FIXME: This shouldn't use hard-coded clock rates, dividers or prescalers.
|
||||
* Should get these from the cfg struct passed to init.
|
||||
*/
|
||||
float PIOS_RTC_Rate()
|
||||
{
|
||||
return (float)(8e6f / 128.0f) / (1 + PIOS_RTC_PRESCALER);
|
||||
}
|
||||
|
||||
float PIOS_RTC_MsPerTick()
|
||||
{
|
||||
return 1000.0f / PIOS_RTC_Rate();
|
||||
}
|
||||
|
||||
/* TODO: This needs a mutex around rtc_callbacks[] */
|
||||
bool PIOS_RTC_RegisterTickCallback(void (*fn)(uint32_t id), uint32_t data)
|
||||
{
|
||||
struct rtc_callback_entry *cb;
|
||||
|
||||
if (rtc_callback_next >= PIOS_RTC_MAX_CALLBACKS) {
|
||||
return false;
|
||||
}
|
||||
|
||||
cb = &rtc_callback_list[rtc_callback_next++];
|
||||
|
||||
cb->fn = fn;
|
||||
cb->data = data;
|
||||
return true;
|
||||
}
|
||||
|
||||
void PIOS_RTC_irq_handler(void)
|
||||
{
|
||||
#if defined(PIOS_INCLUDE_CHIBIOS)
|
||||
CH_IRQ_PROLOGUE();
|
||||
#endif /* defined(PIOS_INCLUDE_CHIBIOS) */
|
||||
|
||||
if (RTC_GetITStatus(RTC_IT_WUT)) {
|
||||
/* Call all registered callbacks */
|
||||
for (uint8_t i = 0; i < rtc_callback_next; i++) {
|
||||
struct rtc_callback_entry *cb = &rtc_callback_list[i];
|
||||
if (cb->fn) {
|
||||
(cb->fn)(cb->data);
|
||||
}
|
||||
}
|
||||
|
||||
/* Clear the RTC Second interrupt */
|
||||
RTC_ClearITPendingBit(RTC_IT_WUT);
|
||||
}
|
||||
|
||||
if (EXTI_GetITStatus(EXTI_Line20) != RESET) {
|
||||
EXTI_ClearITPendingBit(EXTI_Line20);
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_CHIBIOS)
|
||||
CH_IRQ_EPILOGUE();
|
||||
#endif /* defined(PIOS_INCLUDE_CHIBIOS) */
|
||||
}
|
||||
#endif /* if defined(PIOS_INCLUDE_RTC) */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
738
flight/pios/stm32f30x/pios_spi.c
Normal file
738
flight/pios/stm32f30x/pios_spi.c
Normal file
@ -0,0 +1,738 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_SPI SPI Functions
|
||||
* @brief PIOS interface to read and write from SPI ports
|
||||
* @{
|
||||
*
|
||||
* @file pios_spi.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief Hardware Abstraction Layer for SPI ports of STM32
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @notes
|
||||
*
|
||||
* Note that additional chip select lines can be easily added by using
|
||||
* the remaining free GPIOs of the core module. Shared SPI ports should be
|
||||
* arbitrated with (FreeRTOS based) Mutexes to avoid collisions!
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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_SPI
|
||||
|
||||
#include <pios_spi_priv.h>
|
||||
|
||||
static bool PIOS_SPI_validate(__attribute__((unused)) struct pios_spi_dev *com_dev)
|
||||
{
|
||||
/* Should check device magic here */
|
||||
return true;
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
static struct pios_spi_dev *PIOS_SPI_alloc(void)
|
||||
{
|
||||
return pios_malloc(sizeof(struct pios_spi_dev));
|
||||
}
|
||||
#else
|
||||
static struct pios_spi_dev pios_spi_devs[PIOS_SPI_MAX_DEVS];
|
||||
static uint8_t pios_spi_num_devs;
|
||||
static struct pios_spi_dev *PIOS_SPI_alloc(void)
|
||||
{
|
||||
if (pios_spi_num_devs >= PIOS_SPI_MAX_DEVS) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
return &pios_spi_devs[pios_spi_num_devs++];
|
||||
}
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Initialises SPI pins
|
||||
* \param[in] mode currently only mode 0 supported
|
||||
* \return < 0 if initialisation failed
|
||||
*/
|
||||
int32_t PIOS_SPI_Init(uint32_t *spi_id, const struct pios_spi_cfg *cfg)
|
||||
{
|
||||
uint32_t init_ssel = 0;
|
||||
|
||||
PIOS_Assert(spi_id);
|
||||
PIOS_Assert(cfg);
|
||||
|
||||
struct pios_spi_dev *spi_dev;
|
||||
|
||||
spi_dev = (struct pios_spi_dev *)PIOS_SPI_alloc();
|
||||
if (!spi_dev) {
|
||||
goto out_fail;
|
||||
}
|
||||
|
||||
/* Bind the configuration to the device instance */
|
||||
spi_dev->cfg = cfg;
|
||||
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
vSemaphoreCreateBinary(spi_dev->busy);
|
||||
xSemaphoreGive(spi_dev->busy);
|
||||
#else
|
||||
spi_dev->busy = 0;
|
||||
#endif
|
||||
|
||||
/* Disable callback function */
|
||||
spi_dev->callback = NULL;
|
||||
|
||||
/* Set rx/tx dummy bytes to a known value */
|
||||
spi_dev->rx_dummy_byte = 0xFF;
|
||||
spi_dev->tx_dummy_byte = 0xFF;
|
||||
|
||||
switch (spi_dev->cfg->init.SPI_NSS) {
|
||||
case SPI_NSS_Soft:
|
||||
if (spi_dev->cfg->init.SPI_Mode == SPI_Mode_Master) {
|
||||
/* We're a master in soft NSS mode, make sure we see NSS high at all times. */
|
||||
SPI_NSSInternalSoftwareConfig(spi_dev->cfg->regs, SPI_NSSInternalSoft_Set);
|
||||
/* Init as many slave selects as the config advertises. */
|
||||
init_ssel = spi_dev->cfg->slave_count;
|
||||
} else {
|
||||
/* We're a slave in soft NSS mode, make sure we see NSS low at all times. */
|
||||
SPI_NSSInternalSoftwareConfig(spi_dev->cfg->regs, SPI_NSSInternalSoft_Reset);
|
||||
}
|
||||
break;
|
||||
case SPI_NSS_Hard:
|
||||
/* only legal for single-slave config */
|
||||
PIOS_Assert(spi_dev->cfg->slave_count == 1);
|
||||
init_ssel = 1;
|
||||
/* FIXME: Should this also call SPI_SSOutputCmd()? */
|
||||
break;
|
||||
|
||||
default:
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
/* Initialize the GPIO pins */
|
||||
/* note __builtin_ctz() due to the difference between GPIO_PinX and GPIO_PinSourceX */
|
||||
if (spi_dev->cfg->remap) {
|
||||
GPIO_PinAFConfig(spi_dev->cfg->sclk.gpio,
|
||||
__builtin_ctz(spi_dev->cfg->sclk.init.GPIO_Pin),
|
||||
spi_dev->cfg->remap);
|
||||
GPIO_PinAFConfig(spi_dev->cfg->mosi.gpio,
|
||||
__builtin_ctz(spi_dev->cfg->mosi.init.GPIO_Pin),
|
||||
spi_dev->cfg->remap);
|
||||
GPIO_PinAFConfig(spi_dev->cfg->miso.gpio,
|
||||
__builtin_ctz(spi_dev->cfg->miso.init.GPIO_Pin),
|
||||
spi_dev->cfg->remap);
|
||||
for (uint32_t i = 0; i < init_ssel; i++) {
|
||||
GPIO_PinAFConfig(spi_dev->cfg->ssel[i].gpio,
|
||||
__builtin_ctz(spi_dev->cfg->ssel[i].init.GPIO_Pin),
|
||||
spi_dev->cfg->remap);
|
||||
}
|
||||
}
|
||||
|
||||
/* Initialize the GPIO pins */
|
||||
GPIO_Init(spi_dev->cfg->sclk.gpio, (GPIO_InitTypeDef *)&(spi_dev->cfg->sclk.init));
|
||||
GPIO_Init(spi_dev->cfg->mosi.gpio, (GPIO_InitTypeDef *)&(spi_dev->cfg->mosi.init));
|
||||
GPIO_Init(spi_dev->cfg->miso.gpio, (GPIO_InitTypeDef *)&(spi_dev->cfg->miso.init));
|
||||
for (uint32_t i = 0; i < init_ssel; i++) {
|
||||
/* Since we're driving the SSEL pin in software, ensure that the slave is deselected */
|
||||
/* XXX multi-slave support - maybe have another SPI_NSS_ mode? */
|
||||
GPIO_SetBits(spi_dev->cfg->ssel[i].gpio, spi_dev->cfg->ssel[i].init.GPIO_Pin);
|
||||
GPIO_Init(spi_dev->cfg->ssel[i].gpio, (GPIO_InitTypeDef *)&(spi_dev->cfg->ssel[i].init));
|
||||
}
|
||||
|
||||
/* Enable the associated peripheral clock */
|
||||
switch ((uint32_t)spi_dev->cfg->regs) {
|
||||
case (uint32_t)SPI1:
|
||||
/* Enable SPI peripheral clock (APB2 == high speed) */
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_SPI1, ENABLE);
|
||||
break;
|
||||
case (uint32_t)SPI2:
|
||||
/* Enable SPI peripheral clock (APB1 == slow speed) */
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI2, ENABLE);
|
||||
break;
|
||||
case (uint32_t)SPI3:
|
||||
/* Enable SPI peripheral clock (APB1 == slow speed) */
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI3, ENABLE);
|
||||
break;
|
||||
}
|
||||
|
||||
/* Enable DMA clock */
|
||||
RCC_AHBPeriphClockCmd(spi_dev->cfg->dma.ahb_clk, ENABLE);
|
||||
|
||||
/* Configure DMA for SPI Rx */
|
||||
DMA_Cmd(spi_dev->cfg->dma.rx.channel, DISABLE);
|
||||
DMA_Init(spi_dev->cfg->dma.rx.channel, (DMA_InitTypeDef *)&(spi_dev->cfg->dma.rx.init));
|
||||
|
||||
/* Configure DMA for SPI Tx */
|
||||
DMA_Cmd(spi_dev->cfg->dma.tx.channel, DISABLE);
|
||||
DMA_Init(spi_dev->cfg->dma.tx.channel, (DMA_InitTypeDef *)&(spi_dev->cfg->dma.tx.init));
|
||||
|
||||
/* Initialize the SPI block */
|
||||
SPI_I2S_DeInit(spi_dev->cfg->regs);
|
||||
SPI_Init(spi_dev->cfg->regs, (SPI_InitTypeDef *)&(spi_dev->cfg->init));
|
||||
|
||||
/* Configure CRC calculation */
|
||||
if (spi_dev->cfg->use_crc) {
|
||||
SPI_CalculateCRC(spi_dev->cfg->regs, ENABLE);
|
||||
} else {
|
||||
SPI_CalculateCRC(spi_dev->cfg->regs, DISABLE);
|
||||
}
|
||||
|
||||
/* Configure the RX FIFO Threshold -- 8 bits */
|
||||
SPI_RxFIFOThresholdConfig(spi_dev->cfg->regs, SPI_RxFIFOThreshold_QF);
|
||||
|
||||
/* Enable SPI */
|
||||
SPI_Cmd(spi_dev->cfg->regs, ENABLE);
|
||||
|
||||
/* Enable SPI interrupts to DMA */
|
||||
SPI_I2S_DMACmd(spi_dev->cfg->regs, SPI_I2S_DMAReq_Tx | SPI_I2S_DMAReq_Rx, ENABLE);
|
||||
|
||||
/* Configure DMA interrupt */
|
||||
NVIC_Init((NVIC_InitTypeDef *)&(spi_dev->cfg->dma.irq.init));
|
||||
|
||||
*spi_id = (uint32_t)spi_dev;
|
||||
return 0;
|
||||
|
||||
out_fail:
|
||||
return -1;
|
||||
}
|
||||
|
||||
/**
|
||||
* (Re-)initialises SPI peripheral clock rate
|
||||
*
|
||||
* \param[in] spi SPI number (0 or 1)
|
||||
* \param[in] spi_prescaler configures the SPI speed:
|
||||
* <UL>
|
||||
* <LI>PIOS_SPI_PRESCALER_2: sets clock rate 27.7~ nS @ 72 MHz (36 MBit/s) (only supported for spi==0, spi1 uses 4 instead)
|
||||
* <LI>PIOS_SPI_PRESCALER_4: sets clock rate 55.5~ nS @ 72 MHz (18 MBit/s)
|
||||
* <LI>PIOS_SPI_PRESCALER_8: sets clock rate 111.1~ nS @ 72 MHz (9 MBit/s)
|
||||
* <LI>PIOS_SPI_PRESCALER_16: sets clock rate 222.2~ nS @ 72 MHz (4.5 MBit/s)
|
||||
* <LI>PIOS_SPI_PRESCALER_32: sets clock rate 444.4~ nS @ 72 MHz (2.25 MBit/s)
|
||||
* <LI>PIOS_SPI_PRESCALER_64: sets clock rate 888.8~ nS @ 72 MHz (1.125 MBit/s)
|
||||
* <LI>PIOS_SPI_PRESCALER_128: sets clock rate 1.7~ nS @ 72 MHz (0.562 MBit/s)
|
||||
* <LI>PIOS_SPI_PRESCALER_256: sets clock rate 3.5~ nS @ 72 MHz (0.281 MBit/s)
|
||||
* </UL>
|
||||
* \return 0 if no error
|
||||
* \return -1 if disabled SPI port selected
|
||||
* \return -3 if invalid spi_prescaler selected
|
||||
*/
|
||||
int32_t PIOS_SPI_SetClockSpeed(uint32_t spi_id, SPIPrescalerTypeDef spi_prescaler)
|
||||
{
|
||||
struct pios_spi_dev *spi_dev = (struct pios_spi_dev *)spi_id;
|
||||
|
||||
bool valid = PIOS_SPI_validate(spi_dev);
|
||||
|
||||
PIOS_Assert(valid)
|
||||
|
||||
SPI_InitTypeDef SPI_InitStructure;
|
||||
|
||||
if (spi_prescaler >= 8) {
|
||||
/* Invalid prescaler selected */
|
||||
return -3;
|
||||
}
|
||||
|
||||
/* Start with a copy of the default configuration for the peripheral */
|
||||
SPI_InitStructure = spi_dev->cfg->init;
|
||||
|
||||
/* Adjust the prescaler for the peripheral's clock */
|
||||
SPI_InitStructure.SPI_BaudRatePrescaler = ((uint16_t)spi_prescaler & 7) << 3;
|
||||
|
||||
/* Write back the new configuration */
|
||||
SPI_Init(spi_dev->cfg->regs, &SPI_InitStructure);
|
||||
|
||||
PIOS_SPI_TransferByte(spi_id, 0xFF);
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Claim the SPI bus semaphore. Calling the SPI functions does not require this
|
||||
* \param[in] spi SPI number (0 or 1)
|
||||
* \return 0 if no error
|
||||
* \return -1 if timeout before claiming semaphore
|
||||
*/
|
||||
int32_t PIOS_SPI_ClaimBus(uint32_t spi_id)
|
||||
{
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
struct pios_spi_dev *spi_dev = (struct pios_spi_dev *)spi_id;
|
||||
|
||||
bool valid = PIOS_SPI_validate(spi_dev);
|
||||
PIOS_Assert(valid)
|
||||
|
||||
if (xSemaphoreTake(spi_dev->busy, 0xffff) != pdTRUE) {
|
||||
return -1;
|
||||
}
|
||||
#else
|
||||
struct pios_spi_dev *spi_dev = (struct pios_spi_dev *)spi_id;
|
||||
uint32_t timeout = 0xffff;
|
||||
while ((PIOS_SPI_Busy(spi_id) || spi_dev->busy) && --timeout) {
|
||||
;
|
||||
}
|
||||
if (timeout == 0) { // timed out
|
||||
return -1;
|
||||
}
|
||||
|
||||
PIOS_IRQ_Disable();
|
||||
if (spi_dev->busy) {
|
||||
return -1;
|
||||
}
|
||||
spi_dev->busy = 1;
|
||||
PIOS_IRQ_Enable();
|
||||
#endif /* if defined(PIOS_INCLUDE_FREERTOS) */
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Claim the SPI bus semaphore from an ISR. Has no timeout.
|
||||
* \param[in] spi SPI number (0 or 1)
|
||||
* \param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority
|
||||
* task has is now eligible to run, else unchanged
|
||||
* \return 0 if no error
|
||||
* \return -1 if timeout before claiming semaphore
|
||||
*/
|
||||
int32_t PIOS_SPI_ClaimBusISR(uint32_t spi_id, bool *woken)
|
||||
{
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
struct pios_spi_dev *spi_dev = (struct pios_spi_dev *)spi_id;
|
||||
signed portBASE_TYPE higherPriorityTaskWoken = pdFALSE;
|
||||
|
||||
bool valid = PIOS_SPI_validate(spi_dev);
|
||||
PIOS_Assert(valid)
|
||||
|
||||
if (xSemaphoreTakeFromISR(spi_dev->busy, &higherPriorityTaskWoken) != pdTRUE) {
|
||||
return -1;
|
||||
}
|
||||
if (woken) {
|
||||
*woken = *woken || (higherPriorityTaskWoken == pdTRUE);
|
||||
}
|
||||
return 0;
|
||||
|
||||
#else
|
||||
if (woken) {
|
||||
*woken = false;
|
||||
}
|
||||
return PIOS_SPI_ClaimBus(spi_id);
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
* Release the SPI bus semaphore. Calling the SPI functions does not require this
|
||||
* \param[in] spi SPI number (0 or 1)
|
||||
* \return 0 if no error
|
||||
*/
|
||||
int32_t PIOS_SPI_ReleaseBus(uint32_t spi_id)
|
||||
{
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
struct pios_spi_dev *spi_dev = (struct pios_spi_dev *)spi_id;
|
||||
|
||||
bool valid = PIOS_SPI_validate(spi_dev);
|
||||
PIOS_Assert(valid)
|
||||
|
||||
xSemaphoreGive(spi_dev->busy);
|
||||
#else
|
||||
struct pios_spi_dev *spi_dev = (struct pios_spi_dev *)spi_id;
|
||||
PIOS_IRQ_Disable();
|
||||
spi_dev->busy = 0;
|
||||
PIOS_IRQ_Enable();
|
||||
#endif
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Release the SPI bus semaphore from ISR. Calling the SPI functions does not require this
|
||||
* \param[in] spi SPI number (0 or 1)
|
||||
* \param woken[in,out] If non-NULL, will be set to true if woken was false and a higher priority
|
||||
* task has is now eligible to run, else unchanged
|
||||
* \return 0 if no error
|
||||
*/
|
||||
int32_t PIOS_SPI_ReleaseBusISR(uint32_t spi_id, bool *woken)
|
||||
{
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
struct pios_spi_dev *spi_dev = (struct pios_spi_dev *)spi_id;
|
||||
signed portBASE_TYPE higherPriorityTaskWoken = pdFALSE;
|
||||
|
||||
bool valid = PIOS_SPI_validate(spi_dev);
|
||||
PIOS_Assert(valid)
|
||||
|
||||
xSemaphoreGiveFromISR(spi_dev->busy, &higherPriorityTaskWoken);
|
||||
if (woken) {
|
||||
*woken = *woken || (higherPriorityTaskWoken == pdTRUE);
|
||||
}
|
||||
return 0;
|
||||
|
||||
#else
|
||||
if (woken) {
|
||||
*woken = false;
|
||||
}
|
||||
return PIOS_SPI_ReleaseBus(spi_id);
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Controls the RC (Register Clock alias Chip Select) pin of a SPI port
|
||||
* \param[in] spi SPI number (0 or 1)
|
||||
* \param[in] pin_value 0 or 1
|
||||
* \return 0 if no error
|
||||
*/
|
||||
int32_t PIOS_SPI_RC_PinSet(uint32_t spi_id, uint32_t slave_id, uint8_t pin_value)
|
||||
{
|
||||
struct pios_spi_dev *spi_dev = (struct pios_spi_dev *)spi_id;
|
||||
|
||||
bool valid = PIOS_SPI_validate(spi_dev);
|
||||
|
||||
PIOS_Assert(valid)
|
||||
PIOS_Assert(slave_id <= spi_dev->cfg->slave_count)
|
||||
|
||||
/* XXX multi-slave support? */
|
||||
if (pin_value) {
|
||||
GPIO_SetBits(spi_dev->cfg->ssel[slave_id].gpio, spi_dev->cfg->ssel[slave_id].init.GPIO_Pin);
|
||||
} else {
|
||||
GPIO_ResetBits(spi_dev->cfg->ssel[slave_id].gpio, spi_dev->cfg->ssel[slave_id].init.GPIO_Pin);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Transfers a byte to SPI output and reads back the return value from SPI input
|
||||
* \param[in] spi SPI number (0 or 1)
|
||||
* \param[in] b the byte which should be transfered
|
||||
*/
|
||||
int32_t PIOS_SPI_TransferByte(uint32_t spi_id, uint8_t b)
|
||||
{
|
||||
struct pios_spi_dev *spi_dev = (struct pios_spi_dev *)spi_id;
|
||||
|
||||
bool valid = PIOS_SPI_validate(spi_dev);
|
||||
|
||||
PIOS_Assert(valid)
|
||||
|
||||
uint8_t rx_byte;
|
||||
|
||||
/* Make sure the RXNE flag is cleared by reading the DR register */
|
||||
SPI_ReceiveData8(spi_dev->cfg->regs);
|
||||
|
||||
/* Wait until the TXE goes high */
|
||||
while (SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_I2S_FLAG_TXE) == RESET) {
|
||||
;
|
||||
}
|
||||
|
||||
/* Start the transfer */
|
||||
SPI_SendData8(spi_dev->cfg->regs, b);
|
||||
|
||||
/* Wait until there is a byte to read */
|
||||
while (SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_I2S_FLAG_RXNE) == RESET) {
|
||||
;
|
||||
}
|
||||
|
||||
/* Read the rx'd byte */
|
||||
rx_byte = SPI_ReceiveData8(spi_dev->cfg->regs);
|
||||
|
||||
/* Wait until the TXE goes high */
|
||||
while (!(spi_dev->cfg->regs->SR & SPI_I2S_FLAG_TXE)) {
|
||||
;
|
||||
}
|
||||
|
||||
/* Wait for SPI transfer to have fully completed */
|
||||
while (spi_dev->cfg->regs->SR & SPI_I2S_FLAG_BSY) {
|
||||
;
|
||||
}
|
||||
|
||||
/* Return received byte */
|
||||
return rx_byte;
|
||||
}
|
||||
|
||||
/**
|
||||
* Transfers a block of bytes via PIO.
|
||||
*
|
||||
* \param[in] spi_id SPI device handle
|
||||
* \param[in] send_buffer pointer to buffer which should be sent.<BR>
|
||||
* If NULL, 0xff (all-one) will be sent.
|
||||
* \param[in] receive_buffer pointer to buffer which should get the received values.<BR>
|
||||
* If NULL, received bytes will be discarded.
|
||||
* \param[in] len number of bytes which should be transfered
|
||||
* \return >= 0 if no error during transfer
|
||||
* \return -1 if disabled SPI port selected
|
||||
*/
|
||||
int32_t PIOS_SPI_TransferBlock(uint32_t spi_id, const uint8_t *send_buffer, uint8_t *receive_buffer, uint16_t len, __attribute__((unused)) void *callback)
|
||||
{
|
||||
struct pios_spi_dev *spi_dev = (struct pios_spi_dev *)spi_id;
|
||||
uint8_t b;
|
||||
|
||||
bool valid = PIOS_SPI_validate(spi_dev);
|
||||
|
||||
PIOS_Assert(valid)
|
||||
|
||||
while (len--) {
|
||||
/* get the byte to send */
|
||||
b = send_buffer ? *(send_buffer++) : 0xff;
|
||||
|
||||
/* Wait until the TXE goes high */
|
||||
while (SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_I2S_FLAG_TXE) == RESET) {
|
||||
;
|
||||
}
|
||||
|
||||
/* Start the transfer */
|
||||
SPI_SendData8(spi_dev->cfg->regs, b);
|
||||
|
||||
/* Wait until there is a byte to read */
|
||||
while (SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_I2S_FLAG_RXNE) == RESET) {
|
||||
;
|
||||
}
|
||||
|
||||
/* Read the rx'd byte */
|
||||
b = SPI_ReceiveData8(spi_dev->cfg->regs);
|
||||
|
||||
/* save the received byte */
|
||||
if (receive_buffer) {
|
||||
*(receive_buffer++) = b;
|
||||
}
|
||||
}
|
||||
|
||||
/* Wait for SPI transfer to have fully completed */
|
||||
while (spi_dev->cfg->regs->SR & SPI_I2S_FLAG_BSY) {
|
||||
;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Transfers a block of bytes via DMA.
|
||||
* \param[in] spi SPI number (0 or 1)
|
||||
* \param[in] send_buffer pointer to buffer which should be sent.<BR>
|
||||
* If NULL, 0xff (all-one) will be sent.
|
||||
* \param[in] receive_buffer pointer to buffer which should get the received values.<BR>
|
||||
* If NULL, received bytes will be discarded.
|
||||
* \param[in] len number of bytes which should be transfered
|
||||
* \param[in] callback pointer to callback function which will be executed
|
||||
* from DMA channel interrupt once the transfer is finished.
|
||||
* If NULL, no callback function will be used, and PIOS_SPI_TransferBlock() will
|
||||
* block until the transfer is finished.
|
||||
* \return >= 0 if no error during transfer
|
||||
* \return -1 if disabled SPI port selected
|
||||
* \return -3 if function has been called during an ongoing DMA transfer
|
||||
*/
|
||||
int32_t _PIOS_SPI_TransferBlock(uint32_t spi_id, const uint8_t *send_buffer, uint8_t *receive_buffer, uint16_t len, void *callback)
|
||||
{
|
||||
struct pios_spi_dev *spi_dev = (struct pios_spi_dev *)spi_id;
|
||||
|
||||
bool valid = PIOS_SPI_validate(spi_dev);
|
||||
|
||||
PIOS_Assert(valid)
|
||||
|
||||
DMA_InitTypeDef dma_init;
|
||||
|
||||
/* Exit if ongoing transfer */
|
||||
if (DMA_GetCurrDataCounter(spi_dev->cfg->dma.rx.channel)) {
|
||||
return -3;
|
||||
}
|
||||
|
||||
/* Disable the SPI peripheral */
|
||||
SPI_Cmd(spi_dev->cfg->regs, DISABLE);
|
||||
|
||||
/* Disable the DMA channels */
|
||||
DMA_Cmd(spi_dev->cfg->dma.rx.channel, DISABLE);
|
||||
DMA_Cmd(spi_dev->cfg->dma.tx.channel, DISABLE);
|
||||
|
||||
/* Set callback function */
|
||||
spi_dev->callback = callback;
|
||||
|
||||
/*
|
||||
* Configure Rx channel
|
||||
*/
|
||||
|
||||
/* Start with the default configuration for this peripheral */
|
||||
dma_init = spi_dev->cfg->dma.rx.init;
|
||||
|
||||
if (receive_buffer != NULL) {
|
||||
/* Enable memory addr. increment - bytes written into receive buffer */
|
||||
dma_init.DMA_MemoryBaseAddr = (uint32_t)receive_buffer;
|
||||
dma_init.DMA_MemoryInc = DMA_MemoryInc_Enable;
|
||||
} else {
|
||||
/* Disable memory addr. increment - bytes written into dummy buffer */
|
||||
spi_dev->rx_dummy_byte = 0xFF;
|
||||
dma_init.DMA_MemoryBaseAddr = (uint32_t)&spi_dev->rx_dummy_byte;
|
||||
dma_init.DMA_MemoryInc = DMA_MemoryInc_Disable;
|
||||
}
|
||||
if (spi_dev->cfg->use_crc) {
|
||||
/* Make sure the CRC error flag is cleared before we start */
|
||||
SPI_I2S_ClearFlag(spi_dev->cfg->regs, SPI_FLAG_CRCERR);
|
||||
}
|
||||
|
||||
dma_init.DMA_BufferSize = len;
|
||||
DMA_Init(spi_dev->cfg->dma.rx.channel, &(dma_init));
|
||||
|
||||
/*
|
||||
* Configure Tx channel
|
||||
*/
|
||||
|
||||
/* Start with the default configuration for this peripheral */
|
||||
dma_init = spi_dev->cfg->dma.tx.init;
|
||||
|
||||
if (send_buffer != NULL) {
|
||||
/* Enable memory addr. increment - bytes written into receive buffer */
|
||||
dma_init.DMA_MemoryBaseAddr = (uint32_t)send_buffer;
|
||||
dma_init.DMA_MemoryInc = DMA_MemoryInc_Enable;
|
||||
} else {
|
||||
/* Disable memory addr. increment - bytes written into dummy buffer */
|
||||
spi_dev->tx_dummy_byte = 0xFF;
|
||||
dma_init.DMA_MemoryBaseAddr = (uint32_t)&spi_dev->tx_dummy_byte;
|
||||
dma_init.DMA_MemoryInc = DMA_MemoryInc_Disable;
|
||||
}
|
||||
|
||||
if (spi_dev->cfg->use_crc) {
|
||||
/* The last byte of the payload will be replaced with the CRC8 */
|
||||
dma_init.DMA_BufferSize = len - 1;
|
||||
} else {
|
||||
dma_init.DMA_BufferSize = len;
|
||||
}
|
||||
|
||||
DMA_Init(spi_dev->cfg->dma.tx.channel, &(dma_init));
|
||||
|
||||
/* Enable DMA interrupt if callback function active */
|
||||
DMA_ITConfig(spi_dev->cfg->dma.rx.channel, DMA_IT_TC, (callback != NULL) ? ENABLE : DISABLE);
|
||||
|
||||
/* Flush out the CRC registers */
|
||||
SPI_CalculateCRC(spi_dev->cfg->regs, DISABLE);
|
||||
(void)SPI_GetCRC(spi_dev->cfg->regs, SPI_CRC_Rx);
|
||||
SPI_I2S_ClearFlag(spi_dev->cfg->regs, SPI_FLAG_CRCERR);
|
||||
|
||||
/* Make sure to flush out the receive buffer */
|
||||
(void)SPI_I2S_ReceiveData16(spi_dev->cfg->regs);
|
||||
|
||||
if (spi_dev->cfg->use_crc) {
|
||||
/* Need a 0->1 transition to reset the CRC logic */
|
||||
SPI_CalculateCRC(spi_dev->cfg->regs, ENABLE);
|
||||
}
|
||||
|
||||
/* Start DMA transfers */
|
||||
DMA_Cmd(spi_dev->cfg->dma.rx.channel, ENABLE);
|
||||
DMA_Cmd(spi_dev->cfg->dma.tx.channel, ENABLE);
|
||||
|
||||
/* Reenable the SPI device */
|
||||
SPI_Cmd(spi_dev->cfg->regs, ENABLE);
|
||||
|
||||
if (callback) {
|
||||
/* User has requested a callback, don't wait for the transfer to complete. */
|
||||
return 0;
|
||||
}
|
||||
|
||||
/* Wait until all bytes have been transmitted/received */
|
||||
while (DMA_GetCurrDataCounter(spi_dev->cfg->dma.rx.channel)) {
|
||||
;
|
||||
}
|
||||
|
||||
/* Wait for the final bytes of the transfer to complete, including CRC byte(s). */
|
||||
while (!(SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_I2S_FLAG_TXE))) {
|
||||
;
|
||||
}
|
||||
|
||||
/* Wait for the final bytes of the transfer to complete, including CRC byte(s). */
|
||||
while (SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_I2S_FLAG_BSY)) {
|
||||
;
|
||||
}
|
||||
|
||||
/* Check the CRC on the transfer if enabled. */
|
||||
if (spi_dev->cfg->use_crc) {
|
||||
/* Check the SPI CRC error flag */
|
||||
if (SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_FLAG_CRCERR)) {
|
||||
return -4;
|
||||
}
|
||||
}
|
||||
|
||||
/* No error */
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Check if a transfer is in progress
|
||||
* \param[in] spi SPI number (0 or 1)
|
||||
* \return >= 0 if no transfer is in progress
|
||||
* \return -1 if disabled SPI port selected
|
||||
* \return -2 if unsupported SPI port selected
|
||||
* \return -3 if function has been called during an ongoing DMA transfer
|
||||
*/
|
||||
int32_t PIOS_SPI_Busy(uint32_t spi_id)
|
||||
{
|
||||
struct pios_spi_dev *spi_dev = (struct pios_spi_dev *)spi_id;
|
||||
|
||||
bool valid = PIOS_SPI_validate(spi_dev);
|
||||
|
||||
PIOS_Assert(valid)
|
||||
|
||||
/* DMA buffer has data or SPI transmit register not empty or SPI is busy*/
|
||||
if (DMA_GetCurrDataCounter(spi_dev->cfg->dma.rx.channel) ||
|
||||
!SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_I2S_FLAG_TXE) ||
|
||||
SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_I2S_FLAG_BSY)) {
|
||||
return -3;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void PIOS_SPI_SetPrescalar(uint32_t spi_id, uint32_t prescaler)
|
||||
{
|
||||
struct pios_spi_dev *spi_dev = (struct pios_spi_dev *)spi_id;
|
||||
|
||||
bool valid = PIOS_SPI_validate(spi_dev);
|
||||
|
||||
PIOS_Assert(valid);
|
||||
PIOS_Assert(IS_SPI_BAUDRATE_PRESCALER(prescaler));
|
||||
|
||||
spi_dev->cfg->regs->CR1 = (spi_dev->cfg->regs->CR1 & ~0x0038) | prescaler;
|
||||
}
|
||||
|
||||
void PIOS_SPI_IRQ_Handler(uint32_t spi_id)
|
||||
{
|
||||
struct pios_spi_dev *spi_dev = (struct pios_spi_dev *)spi_id;
|
||||
|
||||
bool valid = PIOS_SPI_validate(spi_dev);
|
||||
|
||||
PIOS_Assert(valid)
|
||||
|
||||
DMA_ClearFlag(spi_dev->cfg->dma.irq.flags);
|
||||
|
||||
/* Wait for the final bytes of the transfer to complete, including CRC byte(s). */
|
||||
while (!(SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_I2S_FLAG_TXE))) {
|
||||
;
|
||||
}
|
||||
|
||||
/* Wait for the final bytes of the transfer to complete, including CRC byte(s). */
|
||||
while (SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_I2S_FLAG_BSY)) {
|
||||
;
|
||||
}
|
||||
|
||||
if (spi_dev->callback != NULL) {
|
||||
bool crc_ok = true;
|
||||
uint8_t crc_val;
|
||||
|
||||
if (SPI_I2S_GetFlagStatus(spi_dev->cfg->regs, SPI_FLAG_CRCERR)) {
|
||||
crc_ok = false;
|
||||
SPI_I2S_ClearFlag(spi_dev->cfg->regs, SPI_FLAG_CRCERR);
|
||||
}
|
||||
crc_val = SPI_GetCRC(spi_dev->cfg->regs, SPI_CRC_Rx);
|
||||
spi_dev->callback(crc_ok, crc_val);
|
||||
}
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_SPI */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
283
flight/pios/stm32f30x/pios_sys.c
Normal file
283
flight/pios/stm32f30x/pios_sys.c
Normal file
@ -0,0 +1,283 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_SYS System Functions
|
||||
* @brief PIOS System Initialization code
|
||||
* @{
|
||||
*
|
||||
* @file pios_sys.c
|
||||
* @author Michael Smith Copyright (C) 2011
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2014
|
||||
* @brief Sets up basic STM32 system hardware, functions are called from Main.
|
||||
* @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
|
||||
*/
|
||||
|
||||
/* Project Includes */
|
||||
#include "pios.h"
|
||||
|
||||
#if defined(PIOS_INCLUDE_SYS)
|
||||
|
||||
#define MEM8(addr) (*((volatile uint8_t *)(addr)))
|
||||
|
||||
/* Private Function Prototypes */
|
||||
static void NVIC_Configuration(void);
|
||||
|
||||
/**
|
||||
* Initialises all system peripherals
|
||||
*/
|
||||
void PIOS_SYS_Init(void)
|
||||
{
|
||||
/* Setup STM32 system (RCC, clock, PLL and Flash configuration) - CMSIS Function */
|
||||
SystemInit();
|
||||
SystemCoreClockUpdate(); /* update SystemCoreClock for use elsewhere */
|
||||
|
||||
/*
|
||||
* @todo might make sense to fetch the bus clocks and save them somewhere to avoid
|
||||
* having to use the clunky get-all-clocks API everytime we need one.
|
||||
*/
|
||||
|
||||
/* Initialise Basic NVIC */
|
||||
/* do this early to ensure that we take exceptions in the right place */
|
||||
NVIC_Configuration();
|
||||
|
||||
/* Init the delay system */
|
||||
PIOS_DELAY_Init();
|
||||
|
||||
/*
|
||||
* Turn on all the peripheral clocks.
|
||||
* Micromanaging clocks makes no sense given the power situation in the system, so
|
||||
* light up everything we might reasonably use here and just leave it on.
|
||||
*/
|
||||
RCC_AHBPeriphClockCmd(
|
||||
RCC_AHBPeriph_GPIOA |
|
||||
RCC_AHBPeriph_GPIOB |
|
||||
RCC_AHBPeriph_GPIOC |
|
||||
RCC_AHBPeriph_GPIOD |
|
||||
RCC_AHBPeriph_GPIOE |
|
||||
RCC_AHBPeriph_GPIOF |
|
||||
RCC_AHBPeriph_TS |
|
||||
RCC_AHBPeriph_CRC |
|
||||
RCC_AHBPeriph_FLITF |
|
||||
RCC_AHBPeriph_SRAM |
|
||||
RCC_AHBPeriph_DMA2 |
|
||||
RCC_AHBPeriph_DMA1 |
|
||||
RCC_AHBPeriph_ADC34 |
|
||||
RCC_AHBPeriph_ADC12 |
|
||||
0, ENABLE);
|
||||
|
||||
RCC_APB1PeriphClockCmd(
|
||||
RCC_APB1Periph_TIM2 |
|
||||
RCC_APB1Periph_TIM3 |
|
||||
RCC_APB1Periph_TIM4 |
|
||||
RCC_APB1Periph_TIM6 |
|
||||
RCC_APB1Periph_TIM7 |
|
||||
RCC_APB1Periph_WWDG |
|
||||
RCC_APB1Periph_SPI2 |
|
||||
RCC_APB1Periph_SPI3 |
|
||||
RCC_APB1Periph_USART2 |
|
||||
RCC_APB1Periph_USART3 |
|
||||
RCC_APB1Periph_UART4 |
|
||||
RCC_APB1Periph_UART5 |
|
||||
RCC_APB1Periph_I2C1 |
|
||||
RCC_APB1Periph_I2C2 |
|
||||
RCC_APB1Periph_USB |
|
||||
RCC_APB1Periph_CAN1 |
|
||||
RCC_APB1Periph_PWR |
|
||||
RCC_APB1Periph_DAC |
|
||||
0, ENABLE);
|
||||
|
||||
RCC_APB2PeriphClockCmd(
|
||||
RCC_APB2Periph_TIM1 |
|
||||
RCC_APB2Periph_TIM8 |
|
||||
RCC_APB2Periph_TIM15 |
|
||||
RCC_APB2Periph_TIM16 |
|
||||
RCC_APB2Periph_TIM17 |
|
||||
RCC_APB2Periph_USART1 |
|
||||
RCC_APB2Periph_SPI1 |
|
||||
RCC_APB2Periph_SYSCFG |
|
||||
0, ENABLE);
|
||||
|
||||
/*
|
||||
* Configure all pins as input / pullup to avoid issues with
|
||||
* uncommitted pins, excepting special-function pins that we need to
|
||||
* remain as-is.
|
||||
*/
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
GPIO_StructInit(&GPIO_InitStructure);
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP; // default is un-pulled input
|
||||
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_All;
|
||||
#if (PIOS_USB_ENABLED)
|
||||
GPIO_InitStructure.GPIO_Pin &= ~(GPIO_Pin_11 | GPIO_Pin_12); // leave USB D+/D- alone
|
||||
#endif
|
||||
GPIO_InitStructure.GPIO_Pin &= ~(GPIO_Pin_13 | GPIO_Pin_14 | GPIO_Pin_15); // leave JTAG pins alone
|
||||
GPIO_Init(GPIOA, &GPIO_InitStructure);
|
||||
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_All;
|
||||
GPIO_Init(GPIOB, &GPIO_InitStructure);
|
||||
GPIO_Init(GPIOC, &GPIO_InitStructure);
|
||||
GPIO_Init(GPIOD, &GPIO_InitStructure);
|
||||
GPIO_Init(GPIOE, &GPIO_InitStructure);
|
||||
GPIO_Init(GPIOF, &GPIO_InitStructure);
|
||||
}
|
||||
|
||||
/**
|
||||
* Shutdown PIOS and reset the microcontroller:<BR>
|
||||
* <UL>
|
||||
* <LI>Disable all RTOS tasks
|
||||
* <LI>Disable all interrupts
|
||||
* <LI>Turn off all board LEDs
|
||||
* <LI>Reset STM32
|
||||
* </UL>
|
||||
* \return < 0 if reset failed
|
||||
*/
|
||||
int32_t PIOS_SYS_Reset(void)
|
||||
{
|
||||
// disable all interrupts
|
||||
PIOS_IRQ_Disable();
|
||||
|
||||
// turn off all board LEDs
|
||||
#if defined(PIOS_INCLUDE_LED) && defined(PIOS_LED_HEARTBEAT)
|
||||
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
|
||||
#endif /* PIOS_LED_HEARTBEAT */
|
||||
#if defined(PIOS_INCLUDE_LED) && defined(PIOS_LED_ALARM)
|
||||
PIOS_LED_Off(PIOS_LED_ALARM);
|
||||
#endif /* PIOS_LED_ALARM */
|
||||
|
||||
/* XXX F10x port resets most (but not all) peripherals ... do we care? */
|
||||
|
||||
/* Reset STM32 */
|
||||
NVIC_SystemReset();
|
||||
|
||||
while (1) {
|
||||
;
|
||||
}
|
||||
|
||||
/* We will never reach this point */
|
||||
return -1;
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns the serial number as byte array
|
||||
* param[out] pointer to a byte array which can store at least 12 bytes
|
||||
* (12 bytes returned for STM32)
|
||||
* return < 0 if feature not supported
|
||||
*/
|
||||
int32_t PIOS_SYS_SerialNumberGetBinary(uint8_t *array)
|
||||
{
|
||||
int i;
|
||||
|
||||
/* Stored in the so called "electronic signature" */
|
||||
for (i = 0; i < PIOS_SYS_SERIAL_NUM_BINARY_LEN; ++i) {
|
||||
uint8_t b = MEM8(0x1ffff7ac + i);
|
||||
|
||||
array[i] = b;
|
||||
}
|
||||
|
||||
/* No error */
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns the serial number as a string
|
||||
* param[out] str pointer to a string which can store at least 32 digits + zero terminator!
|
||||
* (24 digits returned for STM32)
|
||||
* return < 0 if feature not supported
|
||||
*/
|
||||
int32_t PIOS_SYS_SerialNumberGet(char *str)
|
||||
{
|
||||
int i;
|
||||
|
||||
/* Stored in the so called "electronic signature" */
|
||||
for (i = 0; i < PIOS_SYS_SERIAL_NUM_ASCII_LEN; ++i) {
|
||||
uint8_t b = MEM8(0x1ffff7ac + (i / 2));
|
||||
if (!(i & 1)) {
|
||||
b >>= 4;
|
||||
}
|
||||
b &= 0x0f;
|
||||
|
||||
str[i] = ((b > 9) ? ('A' - 10) : '0') + b;
|
||||
}
|
||||
str[i] = '\0';
|
||||
|
||||
/* No error */
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Configures Vector Table base location and SysTick
|
||||
*/
|
||||
static void NVIC_Configuration(void)
|
||||
{
|
||||
/* Set the Vector Table base address as specified in .ld file */
|
||||
extern void *pios_isr_vector_table_base;
|
||||
|
||||
NVIC_SetVectorTable((uint32_t)&pios_isr_vector_table_base, 0x0);
|
||||
|
||||
/* 4 bits for Interrupt priorities so no sub priorities */
|
||||
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_4);
|
||||
|
||||
/* Configure HCLK clock as SysTick clock source. */
|
||||
SysTick_CLKSourceConfig(SysTick_CLKSource_HCLK);
|
||||
}
|
||||
|
||||
#ifdef USE_FULL_ASSERT
|
||||
/**
|
||||
* Reports the name of the source file and the source line number
|
||||
* where the assert_param error has occurred.
|
||||
* \param[in] file pointer to the source file name
|
||||
* \param[in] line assert_param error line source number
|
||||
* \retval None
|
||||
*/
|
||||
void assert_failed(uint8_t *file, uint32_t line)
|
||||
{
|
||||
/* When serial debugging is implemented, use something like this. */
|
||||
/* printf("Wrong parameters value: file %s on line %d\r\n", file, line); */
|
||||
|
||||
/* Setup the LEDs to Alternate */
|
||||
#if defined(PIOS_LED_HEARTBEAT)
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT);
|
||||
#endif /* PIOS_LED_HEARTBEAT */
|
||||
#if defined(PIOS_LED_ALARM)
|
||||
PIOS_LED_Off(PIOS_LED_ALARM);
|
||||
#endif /* PIOS_LED_ALARM */
|
||||
|
||||
/* Infinite loop */
|
||||
while (1) {
|
||||
#if defined(PIOS_LED_HEARTBEAT)
|
||||
PIOS_LED_Toggle(PIOS_LED_HEARTBEAT);
|
||||
#endif /* PIOS_LED_HEARTBEAT */
|
||||
#if defined(PIOS_LED_ALARM)
|
||||
PIOS_LED_Toggle(PIOS_LED_ALARM);
|
||||
#endif /* PIOS_LED_ALARM */
|
||||
for (int i = 0; i < 1000000; i++) {
|
||||
;
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif /* ifdef USE_FULL_ASSERT */
|
||||
|
||||
#endif /* if defined(PIOS_INCLUDE_SYS) */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
371
flight/pios/stm32f30x/pios_tim.c
Normal file
371
flight/pios/stm32f30x/pios_tim.c
Normal file
@ -0,0 +1,371 @@
|
||||
#include "pios.h"
|
||||
|
||||
#ifdef PIOS_INCLUDE_TIM
|
||||
|
||||
#include "pios_tim_priv.h"
|
||||
|
||||
enum pios_tim_dev_magic {
|
||||
PIOS_TIM_DEV_MAGIC = 0x87654098,
|
||||
};
|
||||
|
||||
struct pios_tim_dev {
|
||||
enum pios_tim_dev_magic magic;
|
||||
|
||||
const struct pios_tim_channel *channels;
|
||||
uint8_t num_channels;
|
||||
|
||||
const struct pios_tim_callbacks *callbacks;
|
||||
uint32_t context;
|
||||
};
|
||||
|
||||
#if 0
|
||||
static bool PIOS_TIM_validate(struct pios_tim_dev *tim_dev)
|
||||
{
|
||||
return tim_dev->magic == PIOS_TIM_DEV_MAGIC;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_FREERTOS) && 0
|
||||
static struct pios_tim_dev *PIOS_TIM_alloc(void)
|
||||
{
|
||||
struct pios_tim_dev *tim_dev;
|
||||
|
||||
tim_dev = (struct pios_tim_dev *)pios_malloc(sizeof(*tim_dev));
|
||||
if (!tim_dev) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
tim_dev->magic = PIOS_TIM_DEV_MAGIC;
|
||||
return tim_dev;
|
||||
}
|
||||
#else
|
||||
static struct pios_tim_dev pios_tim_devs[PIOS_TIM_MAX_DEVS];
|
||||
static uint8_t pios_tim_num_devs;
|
||||
static struct pios_tim_dev *PIOS_TIM_alloc(void)
|
||||
{
|
||||
struct pios_tim_dev *tim_dev;
|
||||
|
||||
if (pios_tim_num_devs >= PIOS_TIM_MAX_DEVS) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
tim_dev = &pios_tim_devs[pios_tim_num_devs++];
|
||||
tim_dev->magic = PIOS_TIM_DEV_MAGIC;
|
||||
|
||||
return tim_dev;
|
||||
}
|
||||
#endif /* if defined(PIOS_INCLUDE_FREERTOS) && 0 */
|
||||
|
||||
|
||||
int32_t PIOS_TIM_InitClock(const struct pios_tim_clock_cfg *cfg)
|
||||
{
|
||||
PIOS_DEBUG_Assert(cfg);
|
||||
|
||||
/* Configure the dividers for this timer */
|
||||
TIM_TimeBaseInit(cfg->timer, (TIM_TimeBaseInitTypeDef *)cfg->time_base_init);
|
||||
|
||||
/* Configure internal timer clocks */
|
||||
TIM_InternalClockConfig(cfg->timer);
|
||||
|
||||
/* Enable timers */
|
||||
TIM_Cmd(cfg->timer, ENABLE);
|
||||
|
||||
/* Enable Interrupts */
|
||||
NVIC_Init((NVIC_InitTypeDef *)&cfg->irq.init);
|
||||
|
||||
// Advanced timers TIM1 & TIM8 need special handling:
|
||||
// There are up to 4 separate interrupts handlers for each advanced timer, but
|
||||
// pios_tim_clock_cfg has provision for only one irq init, so we take care here
|
||||
// to enable additional irq channels that we intend to use.
|
||||
|
||||
if (cfg->timer == TIM1) {
|
||||
NVIC_InitTypeDef init = cfg->irq.init;
|
||||
init.NVIC_IRQChannel = TIM1_UP_TIM16_IRQn;
|
||||
NVIC_Init(&init);
|
||||
} else if (cfg->timer == TIM8) {
|
||||
NVIC_InitTypeDef init = cfg->irq.init;
|
||||
init.NVIC_IRQChannel = TIM8_UP_IRQn;
|
||||
NVIC_Init(&init);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int32_t PIOS_TIM_InitChannels(uint32_t *tim_id, const struct pios_tim_channel *channels, uint8_t num_channels, const struct pios_tim_callbacks *callbacks, uint32_t context)
|
||||
{
|
||||
PIOS_Assert(channels);
|
||||
PIOS_Assert(num_channels);
|
||||
|
||||
struct pios_tim_dev *tim_dev;
|
||||
tim_dev = (struct pios_tim_dev *)PIOS_TIM_alloc();
|
||||
if (!tim_dev) {
|
||||
goto out_fail;
|
||||
}
|
||||
|
||||
/* Bind the configuration to the device instance */
|
||||
tim_dev->channels = channels;
|
||||
tim_dev->num_channels = num_channels;
|
||||
tim_dev->callbacks = callbacks;
|
||||
tim_dev->context = context;
|
||||
|
||||
/* Configure the pins */
|
||||
for (uint8_t i = 0; i < num_channels; i++) {
|
||||
const struct pios_tim_channel *chan = &(channels[i]);
|
||||
|
||||
GPIO_Init(chan->pin.gpio, (GPIO_InitTypeDef *)&chan->pin.init);
|
||||
|
||||
if (chan->remap) {
|
||||
GPIO_PinAFConfig(chan->pin.gpio, chan->pin.pin_source, chan->remap);
|
||||
}
|
||||
}
|
||||
|
||||
*tim_id = (uint32_t)tim_dev;
|
||||
|
||||
return 0;
|
||||
|
||||
out_fail:
|
||||
return -1;
|
||||
}
|
||||
|
||||
static void PIOS_TIM_generic_irq_handler(TIM_TypeDef *timer)
|
||||
{
|
||||
/* Check for an overflow event on this timer */
|
||||
bool overflow_event = 0;
|
||||
uint16_t overflow_count = false;
|
||||
|
||||
if (TIM_GetITStatus(timer, TIM_IT_Update) == SET) {
|
||||
TIM_ClearITPendingBit(timer, TIM_IT_Update);
|
||||
overflow_count = timer->ARR;
|
||||
overflow_event = true;
|
||||
}
|
||||
|
||||
/* Iterate over all registered clients of the TIM layer to find channels on this timer */
|
||||
for (uint8_t i = 0; i < pios_tim_num_devs; i++) {
|
||||
const struct pios_tim_dev *tim_dev = &pios_tim_devs[i];
|
||||
|
||||
if (!tim_dev->channels || tim_dev->num_channels == 0) {
|
||||
/* No channels to process on this client */
|
||||
continue;
|
||||
}
|
||||
|
||||
for (uint8_t j = 0; j < tim_dev->num_channels; j++) {
|
||||
const struct pios_tim_channel *chan = &tim_dev->channels[j];
|
||||
|
||||
if (chan->timer != timer) {
|
||||
/* channel is not on this timer */
|
||||
continue;
|
||||
}
|
||||
|
||||
/* Figure out which interrupt bit we should be looking at */
|
||||
uint16_t timer_it;
|
||||
switch (chan->timer_chan) {
|
||||
case TIM_Channel_1:
|
||||
timer_it = TIM_IT_CC1;
|
||||
break;
|
||||
case TIM_Channel_2:
|
||||
timer_it = TIM_IT_CC2;
|
||||
break;
|
||||
case TIM_Channel_3:
|
||||
timer_it = TIM_IT_CC3;
|
||||
break;
|
||||
case TIM_Channel_4:
|
||||
timer_it = TIM_IT_CC4;
|
||||
break;
|
||||
default:
|
||||
PIOS_Assert(0);
|
||||
break;
|
||||
}
|
||||
|
||||
bool edge_event;
|
||||
uint16_t edge_count;
|
||||
if (TIM_GetITStatus(chan->timer, timer_it) == SET) {
|
||||
TIM_ClearITPendingBit(chan->timer, timer_it);
|
||||
|
||||
/* Read the current counter */
|
||||
switch (chan->timer_chan) {
|
||||
case TIM_Channel_1:
|
||||
edge_count = TIM_GetCapture1(chan->timer);
|
||||
break;
|
||||
case TIM_Channel_2:
|
||||
edge_count = TIM_GetCapture2(chan->timer);
|
||||
break;
|
||||
case TIM_Channel_3:
|
||||
edge_count = TIM_GetCapture3(chan->timer);
|
||||
break;
|
||||
case TIM_Channel_4:
|
||||
edge_count = TIM_GetCapture4(chan->timer);
|
||||
break;
|
||||
default:
|
||||
PIOS_Assert(0);
|
||||
break;
|
||||
}
|
||||
edge_event = true;
|
||||
} else {
|
||||
edge_event = false;
|
||||
edge_count = 0;
|
||||
}
|
||||
|
||||
if (!tim_dev->callbacks) {
|
||||
/* No callbacks registered, we're done with this channel */
|
||||
continue;
|
||||
}
|
||||
|
||||
/* Generate the appropriate callbacks */
|
||||
if (overflow_event & edge_event) {
|
||||
/*
|
||||
* When both edge and overflow happen in the same interrupt, we
|
||||
* need a heuristic to determine the order of the edge and overflow
|
||||
* events so that the callbacks happen in the right order. If we
|
||||
* get the order wrong, our pulse width calculations could be off by up
|
||||
* to ARR ticks. That could be bad.
|
||||
*
|
||||
* Heuristic: If the edge_count is < 32 ticks above zero then we assume the
|
||||
* edge happened just after the overflow.
|
||||
*/
|
||||
|
||||
if (edge_count < 32) {
|
||||
/* Call the overflow callback first */
|
||||
if (tim_dev->callbacks->overflow) {
|
||||
(*tim_dev->callbacks->overflow)((uint32_t)tim_dev,
|
||||
tim_dev->context,
|
||||
j,
|
||||
overflow_count);
|
||||
}
|
||||
/* Call the edge callback second */
|
||||
if (tim_dev->callbacks->edge) {
|
||||
(*tim_dev->callbacks->edge)((uint32_t)tim_dev,
|
||||
tim_dev->context,
|
||||
j,
|
||||
edge_count);
|
||||
}
|
||||
} else {
|
||||
/* Call the edge callback first */
|
||||
if (tim_dev->callbacks->edge) {
|
||||
(*tim_dev->callbacks->edge)((uint32_t)tim_dev,
|
||||
tim_dev->context,
|
||||
j,
|
||||
edge_count);
|
||||
}
|
||||
/* Call the overflow callback second */
|
||||
if (tim_dev->callbacks->overflow) {
|
||||
(*tim_dev->callbacks->overflow)((uint32_t)tim_dev,
|
||||
tim_dev->context,
|
||||
j,
|
||||
overflow_count);
|
||||
}
|
||||
}
|
||||
} else if (overflow_event && tim_dev->callbacks->overflow) {
|
||||
(*tim_dev->callbacks->overflow)((uint32_t)tim_dev,
|
||||
tim_dev->context,
|
||||
j,
|
||||
overflow_count);
|
||||
} else if (edge_event && tim_dev->callbacks->edge) {
|
||||
(*tim_dev->callbacks->edge)((uint32_t)tim_dev,
|
||||
tim_dev->context,
|
||||
j,
|
||||
edge_count);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* Bind Interrupt Handlers
|
||||
*
|
||||
* Map all valid TIM IRQs to the common interrupt handler
|
||||
* and give it enough context to properly demux the various timers
|
||||
*/
|
||||
void TIM1_CC_IRQHandler(void) __attribute__((alias("PIOS_TIM_1_CC_irq_handler")));
|
||||
static void PIOS_TIM_1_CC_irq_handler(void)
|
||||
{
|
||||
PIOS_TIM_generic_irq_handler(TIM1);
|
||||
}
|
||||
|
||||
// The rest of TIM1 interrupts are overlapped
|
||||
void TIM1_BRK_TIM15_IRQHandler(void) __attribute__((alias("PIOS_TIM_1_BRK_TIM_15_irq_handler")));
|
||||
static void PIOS_TIM_1_BRK_TIM_15_irq_handler(void)
|
||||
{
|
||||
if (TIM_GetITStatus(TIM1, TIM_IT_Break)) {
|
||||
PIOS_TIM_generic_irq_handler(TIM1);
|
||||
} else if (TIM_GetITStatus(TIM15, TIM_IT_Update | TIM_IT_CC1 | TIM_IT_CC2 | TIM_IT_CC3 | TIM_IT_CC4 | TIM_IT_COM | TIM_IT_Trigger | TIM_IT_Break)) {
|
||||
PIOS_TIM_generic_irq_handler(TIM15);
|
||||
}
|
||||
}
|
||||
|
||||
void TIM1_UP_TIM16_IRQHandler(void) __attribute__((alias("PIOS_TIM_1_UP_TIM_16_irq_handler")));
|
||||
static void PIOS_TIM_1_UP_TIM_16_irq_handler(void)
|
||||
{
|
||||
if (TIM_GetITStatus(TIM1, TIM_IT_Update)) {
|
||||
PIOS_TIM_generic_irq_handler(TIM1);
|
||||
} else if (TIM_GetITStatus(TIM16, TIM_IT_Update | TIM_IT_CC1 | TIM_IT_CC2 | TIM_IT_CC3 | TIM_IT_CC4 | TIM_IT_COM | TIM_IT_Trigger | TIM_IT_Break)) {
|
||||
PIOS_TIM_generic_irq_handler(TIM16);
|
||||
}
|
||||
}
|
||||
void TIM1_TRG_COM_TIM17_IRQHandler(void) __attribute__((alias("PIOS_TIM_1_TRG_COM_TIM_17_irq_handler")));
|
||||
static void PIOS_TIM_1_TRG_COM_TIM_17_irq_handler(void)
|
||||
{
|
||||
if (TIM_GetITStatus(TIM1, TIM_IT_Trigger | TIM_IT_COM)) {
|
||||
PIOS_TIM_generic_irq_handler(TIM1);
|
||||
} else if (TIM_GetITStatus(TIM17, TIM_IT_Update | TIM_IT_CC1 | TIM_IT_CC2 | TIM_IT_CC3 | TIM_IT_CC4 | TIM_IT_COM | TIM_IT_Trigger | TIM_IT_Break)) {
|
||||
PIOS_TIM_generic_irq_handler(TIM17);
|
||||
}
|
||||
}
|
||||
|
||||
void TIM2_IRQHandler(void) __attribute__((alias("PIOS_TIM_2_irq_handler")));
|
||||
static void PIOS_TIM_2_irq_handler(void)
|
||||
{
|
||||
PIOS_TIM_generic_irq_handler(TIM2);
|
||||
}
|
||||
|
||||
void TIM3_IRQHandler(void) __attribute__((alias("PIOS_TIM_3_irq_handler")));
|
||||
static void PIOS_TIM_3_irq_handler(void)
|
||||
{
|
||||
PIOS_TIM_generic_irq_handler(TIM3);
|
||||
}
|
||||
|
||||
void TIM4_IRQHandler(void) __attribute__((alias("PIOS_TIM_4_irq_handler")));
|
||||
static void PIOS_TIM_4_irq_handler(void)
|
||||
{
|
||||
PIOS_TIM_generic_irq_handler(TIM4);
|
||||
}
|
||||
|
||||
void TIM6_DAC_IRQHandler(void) __attribute__((alias("PIOS_TIM_6_DAC_irq_handler")));
|
||||
static void PIOS_TIM_6_DAC_irq_handler(void)
|
||||
{
|
||||
// What about DAC irq?
|
||||
if (TIM_GetITStatus(TIM6, TIM_IT_Update | TIM_IT_CC1 | TIM_IT_CC2 | TIM_IT_CC3 | TIM_IT_CC4 | TIM_IT_COM | TIM_IT_Trigger | TIM_IT_Break)) {
|
||||
PIOS_TIM_generic_irq_handler(TIM6);
|
||||
}
|
||||
}
|
||||
|
||||
void TIM7_IRQHandler(void) __attribute__((alias("PIOS_TIM_7_irq_handler")));
|
||||
static void PIOS_TIM_7_irq_handler(void)
|
||||
{
|
||||
PIOS_TIM_generic_irq_handler(TIM7);
|
||||
}
|
||||
|
||||
void TIM8_CC_IRQHandler(void) __attribute__((alias("PIOS_TIM_8_CC_irq_handler")));
|
||||
static void PIOS_TIM_8_CC_irq_handler(void)
|
||||
{
|
||||
PIOS_TIM_generic_irq_handler(TIM8);
|
||||
}
|
||||
|
||||
void TIM8_BRK_IRQHandler(void) __attribute__((alias("PIOS_TIM_8_BRK_irq_handler")));
|
||||
static void PIOS_TIM_8_BRK_irq_handler(void)
|
||||
{
|
||||
PIOS_TIM_generic_irq_handler(TIM8);
|
||||
}
|
||||
|
||||
void TIM8_UP_IRQHandler(void) __attribute__((alias("PIOS_TIM_8_UP_irq_handler")));
|
||||
static void PIOS_TIM_8_UP_irq_handler(void)
|
||||
{
|
||||
PIOS_TIM_generic_irq_handler(TIM8);
|
||||
}
|
||||
|
||||
void TIM8_TRG_COM_IRQHandler(void) __attribute__((alias("PIOS_TIM_8_TRG_COM_irq_handler")));
|
||||
static void PIOS_TIM_8_TRG_COM_irq_handler(void)
|
||||
{
|
||||
PIOS_TIM_generic_irq_handler(TIM8);
|
||||
}
|
||||
|
||||
|
||||
#endif /* PIOS_INCLUDE_TIM */
|
528
flight/pios/stm32f30x/pios_usart.c
Normal file
528
flight/pios/stm32f30x/pios_usart.c
Normal file
@ -0,0 +1,528 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_USART USART Functions
|
||||
* @brief PIOS interface for USART port
|
||||
* @{
|
||||
*
|
||||
* @file pios_usart.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief USART commands. Inits USARTs, controls USARTs & Interupt handlers. (STM32 dependent)
|
||||
* @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_USART
|
||||
|
||||
#include <pios_usart_priv.h>
|
||||
|
||||
/* Provide a COM driver */
|
||||
static void PIOS_USART_ChangeBaud(uint32_t usart_id, uint32_t baud);
|
||||
static void PIOS_USART_ChangeConfig(uint32_t usart_id, enum PIOS_COM_Word_Length word_len, enum PIOS_COM_Parity parity, enum PIOS_COM_StopBits stop_bits, uint32_t baud_rate);
|
||||
static void PIOS_USART_RegisterRxCallback(uint32_t usart_id, pios_com_callback rx_in_cb, uint32_t context);
|
||||
static void PIOS_USART_RegisterTxCallback(uint32_t usart_id, pios_com_callback tx_out_cb, uint32_t context);
|
||||
static void PIOS_USART_TxStart(uint32_t usart_id, uint16_t tx_bytes_avail);
|
||||
static void PIOS_USART_RxStart(uint32_t usart_id, uint16_t rx_bytes_avail);
|
||||
static int32_t PIOS_USART_Ioctl(uint32_t usart_id, uint32_t ctl, void *param);
|
||||
|
||||
const struct pios_com_driver pios_usart_com_driver = {
|
||||
.set_baud = PIOS_USART_ChangeBaud,
|
||||
.set_config = PIOS_USART_ChangeConfig,
|
||||
.tx_start = PIOS_USART_TxStart,
|
||||
.rx_start = PIOS_USART_RxStart,
|
||||
.bind_tx_cb = PIOS_USART_RegisterTxCallback,
|
||||
.bind_rx_cb = PIOS_USART_RegisterRxCallback,
|
||||
.ioctl = PIOS_USART_Ioctl,
|
||||
};
|
||||
|
||||
enum pios_usart_dev_magic {
|
||||
PIOS_USART_DEV_MAGIC = 0x11223344,
|
||||
};
|
||||
|
||||
struct pios_usart_dev {
|
||||
enum pios_usart_dev_magic magic;
|
||||
const struct pios_usart_cfg *cfg;
|
||||
USART_InitTypeDef init;
|
||||
pios_com_callback rx_in_cb;
|
||||
uint32_t rx_in_context;
|
||||
pios_com_callback tx_out_cb;
|
||||
uint32_t tx_out_context;
|
||||
|
||||
uint32_t rx_dropped;
|
||||
uint8_t irq_channel;
|
||||
};
|
||||
|
||||
static bool PIOS_USART_validate(struct pios_usart_dev *usart_dev)
|
||||
{
|
||||
return usart_dev->magic == PIOS_USART_DEV_MAGIC;
|
||||
}
|
||||
|
||||
static int32_t PIOS_USART_SetIrqPrio(struct pios_usart_dev *usart_dev, uint8_t irq_prio)
|
||||
{
|
||||
NVIC_InitTypeDef init = {
|
||||
.NVIC_IRQChannel = usart_dev->irq_channel,
|
||||
.NVIC_IRQChannelPreemptionPriority = irq_prio,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
};
|
||||
|
||||
NVIC_Init(&init);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
static struct pios_usart_dev *PIOS_USART_alloc(void)
|
||||
{
|
||||
struct pios_usart_dev *usart_dev;
|
||||
|
||||
usart_dev = (struct pios_usart_dev *)pios_malloc(sizeof(struct pios_usart_dev));
|
||||
if (!usart_dev) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
memset(usart_dev, 0, sizeof(struct pios_usart_dev));
|
||||
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;
|
||||
|
||||
if (pios_usart_num_devs >= PIOS_USART_MAX_DEVS) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
usart_dev = &pios_usart_devs[pios_usart_num_devs++];
|
||||
|
||||
memset(usart_dev, 0, sizeof(struct pios_usart_dev));
|
||||
usart_dev->magic = PIOS_USART_DEV_MAGIC;
|
||||
|
||||
return usart_dev;
|
||||
}
|
||||
#endif /* if defined(PIOS_INCLUDE_FREERTOS) */
|
||||
|
||||
/* Bind Interrupt Handlers
|
||||
*
|
||||
* Map all valid USART IRQs to the common interrupt handler
|
||||
* and provide storage for a 32-bit device id IRQ to map
|
||||
* each physical IRQ to a specific registered device instance.
|
||||
*/
|
||||
static void PIOS_USART_generic_irq_handler(uint32_t usart_id);
|
||||
|
||||
static uint32_t PIOS_USART_1_id;
|
||||
void USART1_EXTI25_IRQHandler(void) __attribute__((alias("PIOS_USART_1_irq_handler")));
|
||||
static void PIOS_USART_1_irq_handler(void)
|
||||
{
|
||||
PIOS_USART_generic_irq_handler(PIOS_USART_1_id);
|
||||
}
|
||||
|
||||
static uint32_t PIOS_USART_2_id;
|
||||
void USART2_EXTI26_IRQHandler(void) __attribute__((alias("PIOS_USART_2_irq_handler")));
|
||||
static void PIOS_USART_2_irq_handler(void)
|
||||
{
|
||||
PIOS_USART_generic_irq_handler(PIOS_USART_2_id);
|
||||
}
|
||||
|
||||
static uint32_t PIOS_USART_3_id;
|
||||
void USART3_EXTI28_IRQHandler(void) __attribute__((alias("PIOS_USART_3_irq_handler")));
|
||||
static void PIOS_USART_3_irq_handler(void)
|
||||
{
|
||||
PIOS_USART_generic_irq_handler(PIOS_USART_3_id);
|
||||
}
|
||||
|
||||
|
||||
static uint32_t PIOS_UART_4_id;
|
||||
void UART4_EXTI34_IRQHandler(void) __attribute__((alias("PIOS_UART_4_irq_handler")));
|
||||
static void PIOS_UART_4_irq_handler(void)
|
||||
{
|
||||
PIOS_USART_generic_irq_handler(PIOS_UART_4_id);
|
||||
}
|
||||
|
||||
static uint32_t PIOS_UART_5_id;
|
||||
void UART5_EXTI35_IRQHandler(void) __attribute__((alias("PIOS_UART_5_irq_handler")));
|
||||
static void PIOS_UART_5_irq_handler(void)
|
||||
{
|
||||
PIOS_USART_generic_irq_handler(PIOS_UART_5_id);
|
||||
}
|
||||
|
||||
/**
|
||||
* 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;
|
||||
|
||||
/* Set some sane defaults */
|
||||
USART_StructInit(&usart_dev->init);
|
||||
|
||||
/* We will set modes later, depending on installed callbacks */
|
||||
usart_dev->init.USART_Mode = 0;
|
||||
|
||||
*usart_id = (uint32_t)usart_dev;
|
||||
|
||||
/* Configure USART Interrupts */
|
||||
switch ((uint32_t)usart_dev->cfg->regs) {
|
||||
case (uint32_t)USART1:
|
||||
PIOS_USART_1_id = (uint32_t)usart_dev;
|
||||
usart_dev->irq_channel = USART1_IRQn;
|
||||
break;
|
||||
case (uint32_t)USART2:
|
||||
PIOS_USART_2_id = (uint32_t)usart_dev;
|
||||
usart_dev->irq_channel = USART2_IRQn;
|
||||
break;
|
||||
case (uint32_t)USART3:
|
||||
PIOS_USART_3_id = (uint32_t)usart_dev;
|
||||
usart_dev->irq_channel = USART3_IRQn;
|
||||
break;
|
||||
case (uint32_t)UART4:
|
||||
PIOS_UART_4_id = (uint32_t)usart_dev;
|
||||
usart_dev->irq_channel = UART4_IRQn;
|
||||
break;
|
||||
case (uint32_t)UART5:
|
||||
PIOS_UART_5_id = (uint32_t)usart_dev;
|
||||
usart_dev->irq_channel = UART5_IRQn;
|
||||
break;
|
||||
}
|
||||
|
||||
PIOS_USART_SetIrqPrio(usart_dev, PIOS_IRQ_PRIO_MID);
|
||||
|
||||
/* Disable overrun detection */
|
||||
USART_OverrunDetectionConfig(usart_dev->cfg->regs, USART_OVRDetection_Disable);
|
||||
|
||||
return 0;
|
||||
|
||||
out_fail:
|
||||
return -1;
|
||||
}
|
||||
|
||||
static void PIOS_USART_Setup(struct pios_usart_dev *usart_dev)
|
||||
{
|
||||
/* Configure RX GPIO */
|
||||
if ((usart_dev->init.USART_Mode & USART_Mode_Rx) && (usart_dev->cfg->rx.gpio)) {
|
||||
if (usart_dev->cfg->remap) {
|
||||
GPIO_PinAFConfig(usart_dev->cfg->rx.gpio,
|
||||
usart_dev->cfg->rx.pin_source,
|
||||
usart_dev->cfg->remap);
|
||||
}
|
||||
|
||||
GPIO_Init(usart_dev->cfg->rx.gpio, (GPIO_InitTypeDef *)&usart_dev->cfg->rx.init);
|
||||
|
||||
USART_ITConfig(usart_dev->cfg->regs, USART_IT_RXNE, ENABLE);
|
||||
}
|
||||
|
||||
/* Configure TX GPIO */
|
||||
if ((usart_dev->init.USART_Mode & USART_Mode_Tx) && usart_dev->cfg->tx.gpio) {
|
||||
if (usart_dev->cfg->remap) {
|
||||
GPIO_PinAFConfig(usart_dev->cfg->tx.gpio,
|
||||
usart_dev->cfg->tx.pin_source,
|
||||
usart_dev->cfg->remap);
|
||||
}
|
||||
|
||||
GPIO_Init(usart_dev->cfg->tx.gpio, (GPIO_InitTypeDef *)&usart_dev->cfg->tx.init);
|
||||
}
|
||||
|
||||
/* Write new configuration */
|
||||
USART_Init(usart_dev->cfg->regs, &usart_dev->init);
|
||||
|
||||
/*
|
||||
* Re enable USART.
|
||||
*/
|
||||
USART_Cmd(usart_dev->cfg->regs, ENABLE);
|
||||
}
|
||||
|
||||
static void PIOS_USART_RxStart(uint32_t usart_id, __attribute__((unused)) uint16_t rx_bytes_avail)
|
||||
{
|
||||
struct pios_usart_dev *usart_dev = (struct pios_usart_dev *)usart_id;
|
||||
|
||||
bool valid = PIOS_USART_validate(usart_dev);
|
||||
|
||||
PIOS_Assert(valid);
|
||||
|
||||
USART_ITConfig(usart_dev->cfg->regs, USART_IT_RXNE, ENABLE);
|
||||
}
|
||||
static void PIOS_USART_TxStart(uint32_t usart_id, __attribute__((unused)) uint16_t tx_bytes_avail)
|
||||
{
|
||||
struct pios_usart_dev *usart_dev = (struct pios_usart_dev *)usart_id;
|
||||
|
||||
bool valid = PIOS_USART_validate(usart_dev);
|
||||
|
||||
PIOS_Assert(valid);
|
||||
|
||||
USART_ITConfig(usart_dev->cfg->regs, USART_IT_TXE, ENABLE);
|
||||
}
|
||||
|
||||
/**
|
||||
* Changes the baud rate of the USART peripheral without re-initialising.
|
||||
* \param[in] usart_id USART name (GPS, TELEM, AUX)
|
||||
* \param[in] baud Requested baud rate
|
||||
*/
|
||||
static void PIOS_USART_ChangeBaud(uint32_t usart_id, uint32_t baud)
|
||||
{
|
||||
struct pios_usart_dev *usart_dev = (struct pios_usart_dev *)usart_id;
|
||||
|
||||
bool valid = PIOS_USART_validate(usart_dev);
|
||||
|
||||
PIOS_Assert(valid);
|
||||
|
||||
usart_dev->init.USART_BaudRate = baud;
|
||||
|
||||
PIOS_USART_Setup(usart_dev);
|
||||
}
|
||||
|
||||
/**
|
||||
* Changes configuration of the USART peripheral without re-initialising.
|
||||
* \param[in] usart_id USART name (GPS, TELEM, AUX)
|
||||
* \param[in] word_len Requested word length
|
||||
* \param[in] stop_bits Requested stop bits
|
||||
* \param[in] parity Requested parity
|
||||
*
|
||||
*/
|
||||
static void PIOS_USART_ChangeConfig(uint32_t usart_id,
|
||||
enum PIOS_COM_Word_Length word_len,
|
||||
enum PIOS_COM_Parity parity,
|
||||
enum PIOS_COM_StopBits stop_bits,
|
||||
uint32_t baud_rate)
|
||||
{
|
||||
struct pios_usart_dev *usart_dev = (struct pios_usart_dev *)usart_id;
|
||||
|
||||
bool valid = PIOS_USART_validate(usart_dev);
|
||||
|
||||
PIOS_Assert(valid);
|
||||
|
||||
switch (word_len) {
|
||||
case PIOS_COM_Word_length_8b:
|
||||
usart_dev->init.USART_WordLength = USART_WordLength_8b;
|
||||
break;
|
||||
case PIOS_COM_Word_length_9b:
|
||||
usart_dev->init.USART_WordLength = USART_WordLength_9b;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
switch (stop_bits) {
|
||||
case PIOS_COM_StopBits_1:
|
||||
usart_dev->init.USART_StopBits = USART_StopBits_1;
|
||||
break;
|
||||
case PIOS_COM_StopBits_1_5:
|
||||
usart_dev->init.USART_StopBits = USART_StopBits_1_5;
|
||||
break;
|
||||
case PIOS_COM_StopBits_2:
|
||||
usart_dev->init.USART_StopBits = USART_StopBits_2;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
switch (parity) {
|
||||
case PIOS_COM_Parity_No:
|
||||
usart_dev->init.USART_Parity = USART_Parity_No;
|
||||
break;
|
||||
case PIOS_COM_Parity_Even:
|
||||
usart_dev->init.USART_Parity = USART_Parity_Even;
|
||||
break;
|
||||
case PIOS_COM_Parity_Odd:
|
||||
usart_dev->init.USART_Parity = USART_Parity_Odd;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
if (baud_rate) {
|
||||
usart_dev->init.USART_BaudRate = baud_rate;
|
||||
}
|
||||
|
||||
PIOS_USART_Setup(usart_dev);
|
||||
}
|
||||
|
||||
|
||||
static void PIOS_USART_RegisterRxCallback(uint32_t usart_id, pios_com_callback rx_in_cb, uint32_t context)
|
||||
{
|
||||
struct pios_usart_dev *usart_dev = (struct pios_usart_dev *)usart_id;
|
||||
|
||||
bool valid = PIOS_USART_validate(usart_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
|
||||
*/
|
||||
usart_dev->rx_in_context = context;
|
||||
usart_dev->rx_in_cb = rx_in_cb;
|
||||
|
||||
usart_dev->init.USART_Mode |= USART_Mode_Rx;
|
||||
|
||||
PIOS_USART_Setup(usart_dev);
|
||||
}
|
||||
|
||||
static void PIOS_USART_RegisterTxCallback(uint32_t usart_id, pios_com_callback tx_out_cb, uint32_t context)
|
||||
{
|
||||
struct pios_usart_dev *usart_dev = (struct pios_usart_dev *)usart_id;
|
||||
|
||||
bool valid = PIOS_USART_validate(usart_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
|
||||
*/
|
||||
usart_dev->tx_out_context = context;
|
||||
usart_dev->tx_out_cb = tx_out_cb;
|
||||
|
||||
usart_dev->init.USART_Mode |= USART_Mode_Tx;
|
||||
|
||||
PIOS_USART_Setup(usart_dev);
|
||||
}
|
||||
|
||||
static void PIOS_USART_generic_irq_handler(uint32_t usart_id)
|
||||
{
|
||||
struct pios_usart_dev *usart_dev = (struct pios_usart_dev *)usart_id;
|
||||
|
||||
bool valid = PIOS_USART_validate(usart_dev);
|
||||
|
||||
PIOS_Assert(valid);
|
||||
|
||||
/* Force read of dr after sr to make sure to clear error flags */
|
||||
volatile uint16_t sr = usart_dev->cfg->regs->ISR;
|
||||
volatile uint8_t dr = usart_dev->cfg->regs->RDR;
|
||||
|
||||
/* Check if RXNE flag is set */
|
||||
bool rx_need_yield = false;
|
||||
if (sr & USART_ISR_RXNE) {
|
||||
uint8_t byte = dr;
|
||||
if (usart_dev->rx_in_cb) {
|
||||
uint16_t rc;
|
||||
rc = (usart_dev->rx_in_cb)(usart_dev->rx_in_context, &byte, 1, NULL, &rx_need_yield);
|
||||
if (rc < 1) {
|
||||
/* Lost bytes on rx */
|
||||
usart_dev->rx_dropped += 1;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* Check if TXE flag is set */
|
||||
bool tx_need_yield = false;
|
||||
if (sr & USART_ISR_TXE) {
|
||||
if (usart_dev->tx_out_cb) {
|
||||
uint8_t b;
|
||||
uint16_t bytes_to_send;
|
||||
|
||||
bytes_to_send = (usart_dev->tx_out_cb)(usart_dev->tx_out_context, &b, 1, NULL, &tx_need_yield);
|
||||
|
||||
if (bytes_to_send > 0) {
|
||||
/* Send the byte we've been given */
|
||||
usart_dev->cfg->regs->TDR = b;
|
||||
} else {
|
||||
/* No bytes to send, disable TXE interrupt */
|
||||
USART_ITConfig(usart_dev->cfg->regs, USART_IT_TXE, DISABLE);
|
||||
}
|
||||
} else {
|
||||
/* No bytes to send, disable TXE interrupt */
|
||||
USART_ITConfig(usart_dev->cfg->regs, USART_IT_TXE, DISABLE);
|
||||
}
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
if (rx_need_yield || tx_need_yield) {
|
||||
vPortYield();
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_FREERTOS */
|
||||
}
|
||||
|
||||
static int32_t PIOS_USART_Ioctl(uint32_t usart_id, uint32_t ctl, void *param)
|
||||
{
|
||||
struct pios_usart_dev *usart_dev = (struct pios_usart_dev *)usart_id;
|
||||
|
||||
bool valid = PIOS_USART_validate(usart_dev);
|
||||
|
||||
PIOS_Assert(valid);
|
||||
|
||||
/* some sort of locking would be great to have */
|
||||
|
||||
uint32_t cr1_ue = usart_dev->cfg->regs->CR1 & USART_CR1_UE;
|
||||
|
||||
switch (ctl) {
|
||||
case PIOS_IOCTL_USART_SET_INVERTED:
|
||||
{
|
||||
enum PIOS_USART_Inverted inverted = *(enum PIOS_USART_Inverted *)param;
|
||||
|
||||
usart_dev->cfg->regs->CR1 &= ~((uint32_t)USART_CR1_UE);
|
||||
|
||||
if (usart_dev->cfg->rx.gpio != 0) {
|
||||
GPIO_InitTypeDef gpioInit = usart_dev->cfg->rx.init;
|
||||
|
||||
gpioInit.GPIO_PuPd = (inverted & PIOS_USART_Inverted_Rx) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP;
|
||||
|
||||
GPIO_Init(usart_dev->cfg->rx.gpio, &gpioInit);
|
||||
|
||||
USART_InvPinCmd(usart_dev->cfg->regs, USART_InvPin_Rx, (inverted & PIOS_USART_Inverted_Rx) ? ENABLE : DISABLE);
|
||||
}
|
||||
|
||||
if (usart_dev->cfg->tx.gpio != 0) {
|
||||
USART_InvPinCmd(usart_dev->cfg->regs, USART_InvPin_Tx, (inverted & PIOS_USART_Inverted_Tx) ? ENABLE : DISABLE);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case PIOS_IOCTL_USART_SET_SWAPPIN:
|
||||
usart_dev->cfg->regs->CR1 &= ~((uint32_t)USART_CR1_UE);
|
||||
USART_SWAPPinCmd(usart_dev->cfg->regs, *(bool *)param ? ENABLE : DISABLE);
|
||||
break;
|
||||
case PIOS_IOCTL_USART_SET_HALFDUPLEX:
|
||||
usart_dev->cfg->regs->CR1 &= ~((uint32_t)USART_CR1_UE);
|
||||
USART_HalfDuplexCmd(usart_dev->cfg->regs, *(bool *)param ? ENABLE : DISABLE);
|
||||
break;
|
||||
case PIOS_IOCTL_USART_GET_RXGPIO:
|
||||
*(struct stm32_gpio *)param = usart_dev->cfg->rx;
|
||||
break;
|
||||
case PIOS_IOCTL_USART_GET_TXGPIO:
|
||||
*(struct stm32_gpio *)param = usart_dev->cfg->tx;
|
||||
break;
|
||||
default:
|
||||
return -1;
|
||||
}
|
||||
|
||||
usart_dev->cfg->regs->CR1 |= cr1_ue;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_USART */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
290
flight/pios/stm32f30x/pios_usb.c
Normal file
290
flight/pios/stm32f30x/pios_usb.c
Normal file
@ -0,0 +1,290 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_USB USB Setup Functions
|
||||
* @brief PIOS USB device implementation
|
||||
* @{
|
||||
*
|
||||
* @file pios_usb.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2013
|
||||
* @brief USB device functions (STM32 dependent code)
|
||||
* @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
|
||||
*/
|
||||
|
||||
/* Project Includes */
|
||||
#include "pios.h"
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
|
||||
#include "usb_lib.h"
|
||||
#include "pios_usb_board_data.h"
|
||||
|
||||
#include "pios_usb.h"
|
||||
#include "pios_usb_priv.h"
|
||||
|
||||
|
||||
/* Rx/Tx status */
|
||||
static bool transfer_possible = false;
|
||||
|
||||
/* USB activity detection */
|
||||
static volatile bool sof_seen_since_reset = false;
|
||||
|
||||
enum pios_usb_dev_magic {
|
||||
PIOS_USB_DEV_MAGIC = 0x17365904,
|
||||
};
|
||||
|
||||
struct pios_usb_dev {
|
||||
enum pios_usb_dev_magic magic;
|
||||
const struct pios_usb_cfg *cfg;
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief Validate the usb device structure
|
||||
* @returns 0 if valid device or -1 otherwise
|
||||
*/
|
||||
static int32_t PIOS_USB_validate(struct pios_usb_dev *usb_dev)
|
||||
{
|
||||
if (usb_dev == NULL) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (usb_dev->magic != PIOS_USB_DEV_MAGIC) {
|
||||
return -1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
#ifdef PIOS_INCLUDE_FREERTOS
|
||||
static struct pios_usb_dev *PIOS_USB_alloc(void)
|
||||
{
|
||||
struct pios_usb_dev *usb_dev;
|
||||
|
||||
usb_dev = (struct pios_usb_dev *)pios_malloc(sizeof(*usb_dev));
|
||||
if (!usb_dev) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
usb_dev->magic = PIOS_USB_DEV_MAGIC;
|
||||
return usb_dev;
|
||||
}
|
||||
#else
|
||||
static struct pios_usb_dev pios_usb_devs[PIOS_USB_MAX_DEVS];
|
||||
static uint8_t pios_usb_num_devs;
|
||||
static struct pios_usb_dev *PIOS_USB_alloc(void)
|
||||
{
|
||||
struct pios_usb_dev *usb_dev;
|
||||
|
||||
if (pios_usb_num_devs >= PIOS_USB_MAX_DEVS) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
usb_dev = &pios_usb_devs[pios_usb_num_devs++];
|
||||
usb_dev->magic = PIOS_USB_DEV_MAGIC;
|
||||
|
||||
return usb_dev;
|
||||
}
|
||||
#endif /* ifdef PIOS_INCLUDE_FREERTOS */
|
||||
|
||||
/**
|
||||
* Initialises USB COM layer
|
||||
* \return < 0 if initialisation failed
|
||||
* \note Applications shouldn't call this function directly, instead please use \ref PIOS_COM layer functions
|
||||
*/
|
||||
static uint32_t pios_usb_com_id;
|
||||
int32_t PIOS_USB_Init(uint32_t *usb_id, const struct pios_usb_cfg *cfg)
|
||||
{
|
||||
PIOS_Assert(usb_id);
|
||||
PIOS_Assert(cfg);
|
||||
|
||||
struct pios_usb_dev *usb_dev;
|
||||
|
||||
usb_dev = (struct pios_usb_dev *)PIOS_USB_alloc();
|
||||
if (!usb_dev) {
|
||||
goto out_fail;
|
||||
}
|
||||
|
||||
/* Bind the configuration to the device instance */
|
||||
usb_dev->cfg = cfg;
|
||||
|
||||
PIOS_USB_Reenumerate();
|
||||
|
||||
/*
|
||||
* This is a horrible hack to make this available to
|
||||
* the interrupt callbacks. This should go away ASAP.
|
||||
*/
|
||||
pios_usb_com_id = (uintptr_t)usb_dev;
|
||||
|
||||
/* Enable the USB Interrupts */
|
||||
NVIC_Init((NVIC_InitTypeDef *)&usb_dev->cfg->irq.init);
|
||||
|
||||
/* Configure USB D-/D+ (DM/DP) pins */
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_11 | GPIO_Pin_12;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
|
||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
|
||||
GPIO_Init(GPIOA, &GPIO_InitStructure);
|
||||
|
||||
GPIO_PinAFConfig(GPIOA, GPIO_PinSource11, GPIO_AF_14);
|
||||
GPIO_PinAFConfig(GPIOA, GPIO_PinSource12, GPIO_AF_14);
|
||||
|
||||
/* Configure VBUS sense pin */
|
||||
if (usb_dev->cfg->vsense.gpio) {
|
||||
GPIO_Init(usb_dev->cfg->vsense.gpio, (GPIO_InitTypeDef *)&usb_dev->cfg->vsense.init);
|
||||
}
|
||||
|
||||
/* Select USBCLK source */
|
||||
RCC_USBCLKConfig(RCC_USBCLKSource_PLLCLK_1Div5);
|
||||
/* Enable the USB clock */
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USB, ENABLE);
|
||||
|
||||
USB_Init();
|
||||
USB_SIL_Init();
|
||||
|
||||
*usb_id = (uintptr_t)usb_dev;
|
||||
|
||||
return 0; /* No error */
|
||||
|
||||
out_fail:
|
||||
return -1;
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called by the USB driver on cable connection/disconnection
|
||||
* \param[in] connected connection status (1 if connected)
|
||||
* \return < 0 on errors
|
||||
* \note Applications shouldn't call this function directly, instead please use \ref PIOS_COM layer functions
|
||||
*/
|
||||
int32_t PIOS_USB_ChangeConnectionState(bool Connected)
|
||||
{
|
||||
// In all cases: re-initialise USB HID driver
|
||||
if (Connected) {
|
||||
transfer_possible = true;
|
||||
|
||||
// TODO: Check SetEPRxValid(ENDP1);
|
||||
|
||||
#if defined(USB_LED_ON)
|
||||
USB_LED_ON; // turn the USB led on
|
||||
#endif
|
||||
} else {
|
||||
// Cable disconnected: disable transfers
|
||||
transfer_possible = false;
|
||||
|
||||
#if defined(USB_LED_OFF)
|
||||
USB_LED_OFF; // turn the USB led off
|
||||
#endif
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int32_t PIOS_USB_Reenumerate()
|
||||
{
|
||||
/* Force USB reset and power-down (this will also release the USB pins for direct GPIO control) */
|
||||
_SetCNTR(CNTR_FRES | CNTR_PDWN);
|
||||
|
||||
/* Using a "dirty" method to force a re-enumeration: */
|
||||
/* Force DPM (Pin PA12) low for ca. 10 mS before USB Tranceiver will be enabled */
|
||||
/* This overrules the external Pull-Up at PA12, and at least Windows & MacOS will enumerate again */
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
GPIO_StructInit(&GPIO_InitStructure);
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
|
||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||
GPIO_Init(GPIOA, &GPIO_InitStructure);
|
||||
|
||||
PIOS_DELAY_WaitmS(50);
|
||||
|
||||
/* Release power-down, still hold reset */
|
||||
_SetCNTR(CNTR_PDWN);
|
||||
PIOS_DELAY_WaituS(5);
|
||||
|
||||
/* CNTR_FRES = 0 */
|
||||
_SetCNTR(0);
|
||||
|
||||
/* Clear pending interrupts */
|
||||
_SetISTR(0);
|
||||
|
||||
/* set back to alternate function */
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
|
||||
GPIO_Init(GPIOA, &GPIO_InitStructure);
|
||||
|
||||
/* Configure USB clock */
|
||||
/* USBCLK = PLLCLK / 1.5 */
|
||||
RCC_USBCLKConfig(RCC_USBCLKSource_PLLCLK_1Div5);
|
||||
/* Enable USB clock */
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USB, ENABLE);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
bool PIOS_USB_CableConnected(__attribute__((unused)) uint8_t id)
|
||||
{
|
||||
struct pios_usb_dev *usb_dev = (struct pios_usb_dev *)pios_usb_com_id;
|
||||
|
||||
if (PIOS_USB_validate(usb_dev) != 0) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// If board is configured to have a VSENSE pin, use that
|
||||
if (usb_dev->cfg->vsense.gpio != NULL) {
|
||||
return GPIO_ReadInputDataBit(usb_dev->cfg->vsense.gpio, usb_dev->cfg->vsense.init.GPIO_Pin) == Bit_SET;
|
||||
}
|
||||
|
||||
return sof_seen_since_reset;
|
||||
}
|
||||
|
||||
/**
|
||||
* This function returns the connection status of the USB HID interface
|
||||
* \return 1: interface available
|
||||
* \return 0: interface not available
|
||||
* \note Applications shouldn't call this function directly, instead please use \ref PIOS_COM layer functions
|
||||
*/
|
||||
bool PIOS_USB_CheckAvailable(uint32_t id)
|
||||
{
|
||||
struct pios_usb_dev *usb_dev = (struct pios_usb_dev *)pios_usb_com_id;
|
||||
|
||||
if (PIOS_USB_validate(usb_dev) != 0) {
|
||||
return false;
|
||||
}
|
||||
|
||||
return PIOS_USB_CableConnected(id) && transfer_possible;
|
||||
}
|
||||
|
||||
void SOF_Callback(void)
|
||||
{
|
||||
sof_seen_since_reset = true;
|
||||
}
|
||||
|
||||
void SUSP_Callback(void)
|
||||
{
|
||||
sof_seen_since_reset = false;
|
||||
}
|
||||
|
||||
#endif /* if defined(PIOS_INCLUDE_USB) */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
491
flight/pios/stm32f30x/pios_usb_cdc.c
Normal file
491
flight/pios/stm32f30x/pios_usb_cdc.c
Normal file
@ -0,0 +1,491 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_USB_COM USB COM Functions
|
||||
* @brief PIOS USB COM implementation for CDC interfaces
|
||||
* @notes This implements a CDC Serial Port
|
||||
* @{
|
||||
*
|
||||
* @file pios_usb_com_cdc.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief USB COM functions (STM32 dependent code)
|
||||
* @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_USB_CDC
|
||||
|
||||
#include "pios_usb_cdc_priv.h"
|
||||
#include "pios_usb_board_data.h" /* PIOS_BOARD_*_DATA_LENGTH */
|
||||
|
||||
/* STM32 USB Library Definitions */
|
||||
#include "usb_lib.h"
|
||||
|
||||
static void PIOS_USB_CDC_RegisterTxCallback(uint32_t usbcdc_id, pios_com_callback tx_out_cb, uint32_t context);
|
||||
static void PIOS_USB_CDC_RegisterRxCallback(uint32_t usbcdc_id, pios_com_callback rx_in_cb, uint32_t context);
|
||||
static void PIOS_USB_CDC_RegisterBaudRateCallback(uint32_t usbcdc_id, pios_com_callback_baud_rate baud_rate_cb, uint32_t context);
|
||||
static void PIOS_USB_CDC_TxStart(uint32_t usbcdc_id, uint16_t tx_bytes_avail);
|
||||
static void PIOS_USB_CDC_RxStart(uint32_t usbcdc_id, uint16_t rx_bytes_avail);
|
||||
static uint32_t PIOS_USB_CDC_Available(uint32_t usbcdc_id);
|
||||
|
||||
const struct pios_com_driver pios_usb_cdc_com_driver = {
|
||||
.tx_start = PIOS_USB_CDC_TxStart,
|
||||
.rx_start = PIOS_USB_CDC_RxStart,
|
||||
.bind_tx_cb = PIOS_USB_CDC_RegisterTxCallback,
|
||||
.bind_rx_cb = PIOS_USB_CDC_RegisterRxCallback,
|
||||
.bind_baud_rate_cb = PIOS_USB_CDC_RegisterBaudRateCallback,
|
||||
.available = PIOS_USB_CDC_Available,
|
||||
};
|
||||
|
||||
enum pios_usb_cdc_dev_magic {
|
||||
PIOS_USB_CDC_DEV_MAGIC = 0xAABBCCDD,
|
||||
};
|
||||
|
||||
struct pios_usb_cdc_dev {
|
||||
enum pios_usb_cdc_dev_magic magic;
|
||||
const struct pios_usb_cdc_cfg *cfg;
|
||||
|
||||
uint32_t lower_id;
|
||||
|
||||
pios_com_callback rx_in_cb;
|
||||
uint32_t rx_in_context;
|
||||
pios_com_callback tx_out_cb;
|
||||
uint32_t tx_out_context;
|
||||
|
||||
pios_com_callback_baud_rate baud_rate_cb;
|
||||
uint32_t baud_rate_context;
|
||||
|
||||
uint8_t rx_packet_buffer[PIOS_USB_BOARD_CDC_DATA_LENGTH];
|
||||
/*
|
||||
* NOTE: This is -1 as somewhat of a hack. It ensures that we always send packets
|
||||
* that are strictly < maxPacketSize for this interface which means we never have
|
||||
* to bother with zero length packets (ZLP).
|
||||
*/
|
||||
uint8_t tx_packet_buffer[PIOS_USB_BOARD_CDC_DATA_LENGTH - 1];
|
||||
|
||||
uint32_t rx_dropped;
|
||||
uint32_t rx_oversize;
|
||||
};
|
||||
|
||||
static bool PIOS_USB_CDC_validate(struct pios_usb_cdc_dev *usb_cdc_dev)
|
||||
{
|
||||
return usb_cdc_dev->magic == PIOS_USB_CDC_DEV_MAGIC;
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
static struct pios_usb_cdc_dev *PIOS_USB_CDC_alloc(void)
|
||||
{
|
||||
struct pios_usb_cdc_dev *usb_cdc_dev;
|
||||
|
||||
usb_cdc_dev = (struct pios_usb_cdc_dev *)pios_malloc(sizeof(struct pios_usb_cdc_dev));
|
||||
if (!usb_cdc_dev) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
memset(usb_cdc_dev, 0, sizeof(struct pios_usb_cdc_dev));
|
||||
usb_cdc_dev->magic = PIOS_USB_CDC_DEV_MAGIC;
|
||||
return usb_cdc_dev;
|
||||
}
|
||||
#else
|
||||
static struct pios_usb_cdc_dev pios_usb_cdc_devs[PIOS_USB_CDC_MAX_DEVS];
|
||||
static uint8_t pios_usb_cdc_num_devs;
|
||||
static struct pios_usb_cdc_dev *PIOS_USB_CDC_alloc(void)
|
||||
{
|
||||
struct pios_usb_cdc_dev *usb_cdc_dev;
|
||||
|
||||
if (pios_usb_cdc_num_devs >= PIOS_USB_CDC_MAX_DEVS) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
usb_cdc_dev = &pios_usb_cdc_devs[pios_usb_cdc_num_devs++];
|
||||
|
||||
memset(usb_cdc_dev, 0, sizeof(struct pios_usb_cdc_dev));
|
||||
usb_cdc_dev->magic = PIOS_USB_CDC_DEV_MAGIC;
|
||||
|
||||
return usb_cdc_dev;
|
||||
}
|
||||
#endif /* if defined(PIOS_INCLUDE_FREERTOS) */
|
||||
|
||||
static void PIOS_USB_CDC_DATA_EP_IN_Callback(void);
|
||||
static void PIOS_USB_CDC_DATA_EP_OUT_Callback(void);
|
||||
static void PIOS_USB_CDC_CTRL_EP_IN_Callback(void);
|
||||
|
||||
static uint32_t pios_usb_cdc_id;
|
||||
|
||||
/* Need a better way to pull these in */
|
||||
extern void(*pEpInt_IN[7]) (void);
|
||||
extern void(*pEpInt_OUT[7]) (void);
|
||||
|
||||
int32_t PIOS_USB_CDC_Init(uint32_t *usbcdc_id, const struct pios_usb_cdc_cfg *cfg, uint32_t lower_id)
|
||||
{
|
||||
PIOS_Assert(usbcdc_id);
|
||||
PIOS_Assert(cfg);
|
||||
|
||||
struct pios_usb_cdc_dev *usb_cdc_dev;
|
||||
|
||||
usb_cdc_dev = (struct pios_usb_cdc_dev *)PIOS_USB_CDC_alloc();
|
||||
if (!usb_cdc_dev) {
|
||||
goto out_fail;
|
||||
}
|
||||
|
||||
/* Bind the configuration to the device instance */
|
||||
usb_cdc_dev->cfg = cfg;
|
||||
usb_cdc_dev->lower_id = lower_id;
|
||||
|
||||
pios_usb_cdc_id = (uint32_t)usb_cdc_dev;
|
||||
|
||||
/* Bind lower level callbacks into the USB infrastructure */
|
||||
pEpInt_OUT[cfg->ctrl_tx_ep - 1] = PIOS_USB_CDC_CTRL_EP_IN_Callback;
|
||||
pEpInt_IN[cfg->data_tx_ep - 1] = PIOS_USB_CDC_DATA_EP_IN_Callback;
|
||||
pEpInt_OUT[cfg->data_rx_ep - 1] = PIOS_USB_CDC_DATA_EP_OUT_Callback;
|
||||
|
||||
*usbcdc_id = (uint32_t)usb_cdc_dev;
|
||||
|
||||
return 0;
|
||||
|
||||
out_fail:
|
||||
return -1;
|
||||
}
|
||||
|
||||
|
||||
static void PIOS_USB_CDC_RegisterRxCallback(uint32_t usbcdc_id, pios_com_callback rx_in_cb, uint32_t context)
|
||||
{
|
||||
struct pios_usb_cdc_dev *usb_cdc_dev = (struct pios_usb_cdc_dev *)usbcdc_id;
|
||||
|
||||
bool valid = PIOS_USB_CDC_validate(usb_cdc_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
|
||||
*/
|
||||
usb_cdc_dev->rx_in_context = context;
|
||||
usb_cdc_dev->rx_in_cb = rx_in_cb;
|
||||
}
|
||||
|
||||
static void PIOS_USB_CDC_RegisterTxCallback(uint32_t usbcdc_id, pios_com_callback tx_out_cb, uint32_t context)
|
||||
{
|
||||
struct pios_usb_cdc_dev *usb_cdc_dev = (struct pios_usb_cdc_dev *)usbcdc_id;
|
||||
|
||||
bool valid = PIOS_USB_CDC_validate(usb_cdc_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
|
||||
*/
|
||||
usb_cdc_dev->tx_out_context = context;
|
||||
usb_cdc_dev->tx_out_cb = tx_out_cb;
|
||||
}
|
||||
|
||||
static void PIOS_USB_CDC_RxStart(uint32_t usbcdc_id, uint16_t rx_bytes_avail)
|
||||
{
|
||||
struct pios_usb_cdc_dev *usb_cdc_dev = (struct pios_usb_cdc_dev *)usbcdc_id;
|
||||
|
||||
bool valid = PIOS_USB_CDC_validate(usb_cdc_dev);
|
||||
|
||||
PIOS_Assert(valid);
|
||||
|
||||
if (!PIOS_USB_CheckAvailable(usb_cdc_dev->lower_id)) {
|
||||
return;
|
||||
}
|
||||
|
||||
// If endpoint was stalled and there is now space make it valid
|
||||
PIOS_IRQ_Disable();
|
||||
if ((GetEPRxStatus(usb_cdc_dev->cfg->data_rx_ep) != EP_RX_VALID) &&
|
||||
(rx_bytes_avail >= sizeof(usb_cdc_dev->rx_packet_buffer))) {
|
||||
SetEPRxStatus(usb_cdc_dev->cfg->data_rx_ep, EP_RX_VALID);
|
||||
}
|
||||
PIOS_IRQ_Enable();
|
||||
}
|
||||
|
||||
static void PIOS_USB_CDC_SendData(struct pios_usb_cdc_dev *usb_cdc_dev)
|
||||
{
|
||||
uint16_t bytes_to_tx;
|
||||
|
||||
if (!usb_cdc_dev->tx_out_cb) {
|
||||
return;
|
||||
}
|
||||
|
||||
bool need_yield = false;
|
||||
bytes_to_tx = (usb_cdc_dev->tx_out_cb)(usb_cdc_dev->tx_out_context,
|
||||
usb_cdc_dev->tx_packet_buffer,
|
||||
sizeof(usb_cdc_dev->tx_packet_buffer),
|
||||
NULL,
|
||||
&need_yield);
|
||||
if (bytes_to_tx == 0) {
|
||||
return;
|
||||
}
|
||||
|
||||
UserToPMABufferCopy(usb_cdc_dev->tx_packet_buffer,
|
||||
GetEPTxAddr(usb_cdc_dev->cfg->data_tx_ep),
|
||||
bytes_to_tx);
|
||||
SetEPTxCount(usb_cdc_dev->cfg->data_tx_ep, bytes_to_tx);
|
||||
SetEPTxValid(usb_cdc_dev->cfg->data_tx_ep);
|
||||
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
if (need_yield) {
|
||||
vPortYield();
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_FREERTOS */
|
||||
}
|
||||
|
||||
static void PIOS_USB_CDC_TxStart(uint32_t usbcdc_id, __attribute__((unused)) uint16_t tx_bytes_avail)
|
||||
{
|
||||
struct pios_usb_cdc_dev *usb_cdc_dev = (struct pios_usb_cdc_dev *)usbcdc_id;
|
||||
|
||||
bool valid = PIOS_USB_CDC_validate(usb_cdc_dev);
|
||||
|
||||
PIOS_Assert(valid);
|
||||
|
||||
if (!PIOS_USB_CheckAvailable(usb_cdc_dev->lower_id)) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (GetEPTxStatus(usb_cdc_dev->cfg->data_tx_ep) == EP_TX_VALID) {
|
||||
/* Endpoint is already transmitting */
|
||||
return;
|
||||
}
|
||||
|
||||
PIOS_USB_CDC_SendData(usb_cdc_dev);
|
||||
}
|
||||
|
||||
static void PIOS_USB_CDC_DATA_EP_IN_Callback(void)
|
||||
{
|
||||
struct pios_usb_cdc_dev *usb_cdc_dev = (struct pios_usb_cdc_dev *)pios_usb_cdc_id;
|
||||
|
||||
bool valid = PIOS_USB_CDC_validate(usb_cdc_dev);
|
||||
|
||||
PIOS_Assert(valid);
|
||||
|
||||
PIOS_USB_CDC_SendData(usb_cdc_dev);
|
||||
}
|
||||
|
||||
static void PIOS_USB_CDC_DATA_EP_OUT_Callback(void)
|
||||
{
|
||||
struct pios_usb_cdc_dev *usb_cdc_dev = (struct pios_usb_cdc_dev *)pios_usb_cdc_id;
|
||||
|
||||
bool valid = PIOS_USB_CDC_validate(usb_cdc_dev);
|
||||
|
||||
PIOS_Assert(valid);
|
||||
|
||||
uint32_t DataLength;
|
||||
|
||||
/* Get the number of received data on the selected Endpoint */
|
||||
DataLength = GetEPRxCount(usb_cdc_dev->cfg->data_rx_ep);
|
||||
if (DataLength > sizeof(usb_cdc_dev->rx_packet_buffer)) {
|
||||
usb_cdc_dev->rx_oversize++;
|
||||
DataLength = sizeof(usb_cdc_dev->rx_packet_buffer);
|
||||
}
|
||||
|
||||
/* Use the memory interface function to read from the selected endpoint */
|
||||
PMAToUserBufferCopy((uint8_t *)usb_cdc_dev->rx_packet_buffer,
|
||||
GetEPRxAddr(usb_cdc_dev->cfg->data_rx_ep),
|
||||
DataLength);
|
||||
|
||||
if (!usb_cdc_dev->rx_in_cb) {
|
||||
/* No Rx call back registered, disable the receiver */
|
||||
SetEPRxStatus(usb_cdc_dev->cfg->data_rx_ep, EP_RX_NAK);
|
||||
return;
|
||||
}
|
||||
|
||||
uint16_t headroom;
|
||||
bool need_yield = false;
|
||||
uint16_t rc;
|
||||
rc = (usb_cdc_dev->rx_in_cb)(usb_cdc_dev->rx_in_context,
|
||||
usb_cdc_dev->rx_packet_buffer,
|
||||
DataLength,
|
||||
&headroom,
|
||||
&need_yield);
|
||||
|
||||
if (rc < DataLength) {
|
||||
/* Lost bytes on rx */
|
||||
usb_cdc_dev->rx_dropped += (DataLength - rc);
|
||||
}
|
||||
|
||||
if (headroom >= sizeof(usb_cdc_dev->rx_packet_buffer)) {
|
||||
/* We have room for a maximum length message */
|
||||
SetEPRxStatus(usb_cdc_dev->cfg->data_rx_ep, EP_RX_VALID);
|
||||
} else {
|
||||
/* Not enough room left for a message, apply backpressure */
|
||||
SetEPRxStatus(usb_cdc_dev->cfg->data_rx_ep, EP_RX_NAK);
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
if (need_yield) {
|
||||
vPortYield();
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_FREERTOS */
|
||||
}
|
||||
|
||||
static uint16_t control_line_state;
|
||||
RESULT PIOS_USB_CDC_SetControlLineState(void)
|
||||
{
|
||||
struct pios_usb_cdc_dev *usb_cdc_dev = (struct pios_usb_cdc_dev *)pios_usb_cdc_id;
|
||||
|
||||
bool valid = PIOS_USB_CDC_validate(usb_cdc_dev);
|
||||
|
||||
if (!valid) {
|
||||
/* No CDC interface is configured */
|
||||
return USB_UNSUPPORT;
|
||||
}
|
||||
|
||||
uint8_t wValue0 = pInformation->USBwValue0;
|
||||
uint8_t wValue1 = pInformation->USBwValue1;
|
||||
|
||||
control_line_state = wValue1 << 8 | wValue0;
|
||||
|
||||
return USB_SUCCESS;
|
||||
}
|
||||
|
||||
static uint32_t PIOS_USB_CDC_Available(uint32_t usbcdc_id)
|
||||
{
|
||||
struct pios_usb_cdc_dev *usb_cdc_dev = (struct pios_usb_cdc_dev *)usbcdc_id;
|
||||
|
||||
bool valid = PIOS_USB_CDC_validate(usb_cdc_dev);
|
||||
|
||||
PIOS_Assert(valid);
|
||||
|
||||
return (PIOS_USB_CheckAvailable(usb_cdc_dev->lower_id) &&
|
||||
(control_line_state & USB_CDC_CONTROL_LINE_STATE_DTE_PRESENT)) ? COM_AVAILABLE_RXTX : COM_AVAILABLE_NONE;
|
||||
}
|
||||
|
||||
static struct usb_cdc_line_coding line_coding = {
|
||||
.dwDTERate = htousbl(57600),
|
||||
.bCharFormat = USB_CDC_LINE_CODING_STOP_1,
|
||||
.bParityType = USB_CDC_LINE_CODING_PARITY_NONE,
|
||||
.bDataBits = 8,
|
||||
};
|
||||
|
||||
uint8_t *PIOS_USB_CDC_SetLineCoding(uint16_t Length)
|
||||
{
|
||||
struct pios_usb_cdc_dev *usb_cdc_dev = (struct pios_usb_cdc_dev *)pios_usb_cdc_id;
|
||||
|
||||
bool valid = PIOS_USB_CDC_validate(usb_cdc_dev);
|
||||
|
||||
if (!valid) {
|
||||
/* No CDC interface is configured */
|
||||
return NULL;
|
||||
}
|
||||
|
||||
if (Length == 0) {
|
||||
/* Report the number of bytes we're prepared to consume */
|
||||
pInformation->Ctrl_Info.Usb_wLength = sizeof(line_coding);
|
||||
pInformation->Ctrl_Info.Usb_rLength = sizeof(line_coding);
|
||||
return NULL;
|
||||
} else {
|
||||
/* Give out a pointer to the data struct */
|
||||
return (uint8_t *)&line_coding;
|
||||
}
|
||||
}
|
||||
|
||||
const uint8_t *PIOS_USB_CDC_GetLineCoding(uint16_t Length)
|
||||
{
|
||||
struct pios_usb_cdc_dev *usb_cdc_dev = (struct pios_usb_cdc_dev *)pios_usb_cdc_id;
|
||||
|
||||
bool valid = PIOS_USB_CDC_validate(usb_cdc_dev);
|
||||
|
||||
if (!valid) {
|
||||
/* No CDC interface is configured */
|
||||
return NULL;
|
||||
}
|
||||
|
||||
if (Length == 0) {
|
||||
pInformation->Ctrl_Info.Usb_wLength = sizeof(line_coding);
|
||||
return NULL;
|
||||
} else {
|
||||
return (uint8_t *)&line_coding;
|
||||
}
|
||||
}
|
||||
|
||||
struct usb_cdc_serial_state_report uart_state = {
|
||||
.bmRequestType = 0xA1,
|
||||
.bNotification = USB_CDC_NOTIFICATION_SERIAL_STATE,
|
||||
.wValue = 0,
|
||||
.wIndex = htousbs(1),
|
||||
.wLength = htousbs(2),
|
||||
.bmUartState = htousbs(0),
|
||||
};
|
||||
|
||||
static void PIOS_USB_CDC_CTRL_EP_IN_Callback(void)
|
||||
{
|
||||
struct pios_usb_cdc_dev *usb_cdc_dev = (struct pios_usb_cdc_dev *)pios_usb_cdc_id;
|
||||
|
||||
bool valid = PIOS_USB_CDC_validate(usb_cdc_dev);
|
||||
|
||||
PIOS_Assert(valid);
|
||||
|
||||
/* Give back UART State Bitmap */
|
||||
/* UART State Bitmap
|
||||
* 15-7: reserved
|
||||
* 6: bOverRun overrun error
|
||||
* 5: bParity parity error
|
||||
* 4: bFraming framing error
|
||||
* 3: bRingSignal RI
|
||||
* 2: bBreak break reception
|
||||
* 1: bTxCarrier DSR
|
||||
* 0: bRxCarrier DCD
|
||||
*/
|
||||
uart_state.bmUartState = htousbs(0x0003);
|
||||
|
||||
UserToPMABufferCopy((uint8_t *)&uart_state,
|
||||
GetEPTxAddr(usb_cdc_dev->cfg->ctrl_tx_ep),
|
||||
sizeof(uart_state));
|
||||
SetEPTxCount(usb_cdc_dev->cfg->ctrl_tx_ep, PIOS_USB_BOARD_CDC_MGMT_LENGTH);
|
||||
SetEPTxValid(usb_cdc_dev->cfg->ctrl_tx_ep);
|
||||
}
|
||||
|
||||
static void PIOS_USB_CDC_RegisterBaudRateCallback(uint32_t usbcdc_id, pios_com_callback_baud_rate baud_rate_cb, uint32_t context)
|
||||
{
|
||||
struct pios_usb_cdc_dev *usb_cdc_dev = (struct pios_usb_cdc_dev *)usbcdc_id;
|
||||
|
||||
bool valid = PIOS_USB_CDC_validate(usb_cdc_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
|
||||
*/
|
||||
usb_cdc_dev->baud_rate_context = context;
|
||||
usb_cdc_dev->baud_rate_cb = baud_rate_cb;
|
||||
}
|
||||
|
||||
void PIOS_USB_CDC_SetLineCoding_Completed()
|
||||
{
|
||||
struct pios_usb_cdc_dev *usb_cdc_dev = (struct pios_usb_cdc_dev *)pios_usb_cdc_id;
|
||||
|
||||
bool valid = PIOS_USB_CDC_validate(usb_cdc_dev);
|
||||
|
||||
if (!valid) {
|
||||
/* No CDC interface is configured */
|
||||
return;
|
||||
}
|
||||
|
||||
if (usb_cdc_dev->baud_rate_cb) {
|
||||
usb_cdc_dev->baud_rate_cb(usb_cdc_dev->baud_rate_context, usbltoh(line_coding.dwDTERate));
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB_CDC */
|
372
flight/pios/stm32f30x/pios_usb_hid.c
Normal file
372
flight/pios/stm32f30x/pios_usb_hid.c
Normal file
@ -0,0 +1,372 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_USB_HID USB COM Functions
|
||||
* @brief PIOS USB COM implementation for HID interfaces
|
||||
* @notes This implements serial emulation over HID reports
|
||||
* @{
|
||||
*
|
||||
* @file pios_usb_hid.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2014
|
||||
* @author dRonin, http://dronin.org, Copyright (C) 2016
|
||||
* @brief USB COM functions (STM32 dependent code)
|
||||
* @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
|
||||
*/
|
||||
|
||||
/* Project Includes */
|
||||
#include "pios.h"
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_HID)
|
||||
|
||||
#include "pios_usb.h"
|
||||
#include "pios_usb_hid_priv.h"
|
||||
#include "pios_usb_board_data.h" /* PIOS_BOARD_*_DATA_LENGTH */
|
||||
|
||||
/* STM32 USB Library Definitions */
|
||||
#include "usb_lib.h"
|
||||
|
||||
static void PIOS_USB_HID_RegisterTxCallback(uint32_t usbhid_id, pios_com_callback tx_out_cb, uint32_t context);
|
||||
static void PIOS_USB_HID_RegisterRxCallback(uint32_t usbhid_id, pios_com_callback rx_in_cb, uint32_t context);
|
||||
static void PIOS_USB_HID_TxStart(uint32_t usbhid_id, uint16_t tx_bytes_avail);
|
||||
static void PIOS_USB_HID_RxStart(uint32_t usbhid_id, uint16_t rx_bytes_avail);
|
||||
static uint32_t PIOS_USB_HID_Available(uint32_t usbhid_id);
|
||||
|
||||
const struct pios_com_driver pios_usb_hid_com_driver = {
|
||||
.tx_start = PIOS_USB_HID_TxStart,
|
||||
.rx_start = PIOS_USB_HID_RxStart,
|
||||
.bind_tx_cb = PIOS_USB_HID_RegisterTxCallback,
|
||||
.bind_rx_cb = PIOS_USB_HID_RegisterRxCallback,
|
||||
.available = PIOS_USB_HID_Available,
|
||||
};
|
||||
|
||||
enum pios_usb_hid_dev_magic {
|
||||
PIOS_USB_HID_DEV_MAGIC = 0xAA00BB00,
|
||||
};
|
||||
|
||||
struct pios_usb_hid_dev {
|
||||
enum pios_usb_hid_dev_magic magic;
|
||||
const struct pios_usb_hid_cfg *cfg;
|
||||
|
||||
uint32_t lower_id;
|
||||
|
||||
pios_com_callback rx_in_cb;
|
||||
uint32_t rx_in_context;
|
||||
pios_com_callback tx_out_cb;
|
||||
uint32_t tx_out_context;
|
||||
|
||||
uint8_t rx_packet_buffer[PIOS_USB_BOARD_HID_DATA_LENGTH];
|
||||
uint8_t tx_packet_buffer[PIOS_USB_BOARD_HID_DATA_LENGTH];
|
||||
|
||||
uint32_t rx_dropped;
|
||||
uint32_t rx_oversize;
|
||||
};
|
||||
|
||||
static bool PIOS_USB_HID_validate(struct pios_usb_hid_dev *usb_hid_dev)
|
||||
{
|
||||
return usb_hid_dev->magic == PIOS_USB_HID_DEV_MAGIC;
|
||||
}
|
||||
|
||||
#ifdef PIOS_INCLUDE_FREERTOS
|
||||
static struct pios_usb_hid_dev *PIOS_USB_HID_alloc(void)
|
||||
{
|
||||
struct pios_usb_hid_dev *usb_hid_dev;
|
||||
|
||||
usb_hid_dev = (struct pios_usb_hid_dev *)pios_malloc(sizeof(struct pios_usb_hid_dev));
|
||||
if (!usb_hid_dev) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
memset(usb_hid_dev, 0, sizeof(struct pios_usb_hid_dev));
|
||||
usb_hid_dev->magic = PIOS_USB_HID_DEV_MAGIC;
|
||||
return usb_hid_dev;
|
||||
}
|
||||
#else
|
||||
static struct pios_usb_hid_dev pios_usb_hid_devs[PIOS_USB_HID_MAX_DEVS];
|
||||
static uint8_t pios_usb_hid_num_devs;
|
||||
static struct pios_usb_hid_dev *PIOS_USB_HID_alloc(void)
|
||||
{
|
||||
struct pios_usb_hid_dev *usb_hid_dev;
|
||||
|
||||
if (pios_usb_hid_num_devs >= PIOS_USB_HID_MAX_DEVS) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
usb_hid_dev = &pios_usb_hid_devs[pios_usb_hid_num_devs++];
|
||||
|
||||
memset(usb_hid_dev, 0, sizeof(struct pios_usb_hid_dev));
|
||||
usb_hid_dev->magic = PIOS_USB_HID_DEV_MAGIC;
|
||||
|
||||
return usb_hid_dev;
|
||||
}
|
||||
#endif /* ifdef PIOS_INCLUDE_FREERTOS */
|
||||
|
||||
static void PIOS_USB_HID_EP_IN_Callback(void);
|
||||
static void PIOS_USB_HID_EP_OUT_Callback(void);
|
||||
|
||||
static uint32_t pios_usb_hid_id;
|
||||
|
||||
/* Need a better way to pull these in */
|
||||
extern void(*pEpInt_IN[7]) (void);
|
||||
extern void(*pEpInt_OUT[7]) (void);
|
||||
|
||||
int32_t PIOS_USB_HID_Init(uint32_t *usbhid_id, const struct pios_usb_hid_cfg *cfg, uint32_t lower_id)
|
||||
{
|
||||
PIOS_Assert(usbhid_id);
|
||||
PIOS_Assert(cfg);
|
||||
|
||||
struct pios_usb_hid_dev *usb_hid_dev;
|
||||
|
||||
usb_hid_dev = (struct pios_usb_hid_dev *)PIOS_USB_HID_alloc();
|
||||
if (!usb_hid_dev) {
|
||||
goto out_fail;
|
||||
}
|
||||
|
||||
/* Bind the configuration to the device instance */
|
||||
usb_hid_dev->cfg = cfg;
|
||||
usb_hid_dev->lower_id = lower_id;
|
||||
|
||||
pios_usb_hid_id = (uint32_t)usb_hid_dev;
|
||||
|
||||
/* Bind lower level callbacks into the USB infrastructure */
|
||||
pEpInt_IN[cfg->data_tx_ep - 1] = PIOS_USB_HID_EP_IN_Callback;
|
||||
pEpInt_OUT[cfg->data_rx_ep - 1] = PIOS_USB_HID_EP_OUT_Callback;
|
||||
|
||||
*usbhid_id = (uint32_t)usb_hid_dev;
|
||||
|
||||
return 0;
|
||||
|
||||
out_fail:
|
||||
return -1;
|
||||
}
|
||||
|
||||
|
||||
static void PIOS_USB_HID_SendReport(struct pios_usb_hid_dev *usb_hid_dev)
|
||||
{
|
||||
uint16_t bytes_to_tx;
|
||||
|
||||
if (!usb_hid_dev->tx_out_cb) {
|
||||
return;
|
||||
}
|
||||
|
||||
bool need_yield = false;
|
||||
#ifdef PIOS_USB_BOARD_BL_HID_HAS_NO_LENGTH_BYTE
|
||||
bytes_to_tx = (usb_hid_dev->tx_out_cb)(usb_hid_dev->tx_out_context,
|
||||
&usb_hid_dev->tx_packet_buffer[1],
|
||||
sizeof(usb_hid_dev->tx_packet_buffer) - 1,
|
||||
NULL,
|
||||
&need_yield);
|
||||
#else
|
||||
bytes_to_tx = (usb_hid_dev->tx_out_cb)(usb_hid_dev->tx_out_context,
|
||||
&usb_hid_dev->tx_packet_buffer[2],
|
||||
sizeof(usb_hid_dev->tx_packet_buffer) - 2,
|
||||
NULL,
|
||||
&need_yield);
|
||||
#endif
|
||||
if (bytes_to_tx == 0) {
|
||||
return;
|
||||
}
|
||||
|
||||
/* Always set type as report ID */
|
||||
usb_hid_dev->tx_packet_buffer[0] = 1;
|
||||
|
||||
#ifdef PIOS_USB_BOARD_BL_HID_HAS_NO_LENGTH_BYTE
|
||||
UserToPMABufferCopy(usb_hid_dev->tx_packet_buffer,
|
||||
GetEPTxAddr(usb_hid_dev->cfg->data_tx_ep),
|
||||
bytes_to_tx + 1);
|
||||
#else
|
||||
usb_hid_dev->tx_packet_buffer[1] = bytes_to_tx;
|
||||
UserToPMABufferCopy(usb_hid_dev->tx_packet_buffer,
|
||||
GetEPTxAddr(usb_hid_dev->cfg->data_tx_ep),
|
||||
bytes_to_tx + 2);
|
||||
#endif
|
||||
/* Is this correct? Why do we always send the whole buffer? */
|
||||
SetEPTxCount(usb_hid_dev->cfg->data_tx_ep, sizeof(usb_hid_dev->tx_packet_buffer));
|
||||
SetEPTxValid(usb_hid_dev->cfg->data_tx_ep);
|
||||
}
|
||||
|
||||
static void PIOS_USB_HID_RxStart(uint32_t usbhid_id, uint16_t rx_bytes_avail)
|
||||
{
|
||||
struct pios_usb_hid_dev *usb_hid_dev = (struct pios_usb_hid_dev *)usbhid_id;
|
||||
|
||||
bool valid = PIOS_USB_HID_validate(usb_hid_dev);
|
||||
|
||||
PIOS_Assert(valid);
|
||||
|
||||
if (!PIOS_USB_CheckAvailable(usb_hid_dev->lower_id)) {
|
||||
return;
|
||||
}
|
||||
|
||||
// If endpoint was stalled and there is now space make it valid
|
||||
#ifdef PIOS_USB_BOARD_BL_HID_HAS_NO_LENGTH_BYTE
|
||||
uint16_t max_payload_length = PIOS_USB_BOARD_HID_DATA_LENGTH - 1;
|
||||
#else
|
||||
uint16_t max_payload_length = PIOS_USB_BOARD_HID_DATA_LENGTH - 2;
|
||||
#endif
|
||||
|
||||
PIOS_IRQ_Disable();
|
||||
if ((GetEPRxStatus(usb_hid_dev->cfg->data_rx_ep) != EP_RX_VALID) &&
|
||||
(rx_bytes_avail >= max_payload_length)) {
|
||||
SetEPRxStatus(usb_hid_dev->cfg->data_rx_ep, EP_RX_VALID);
|
||||
}
|
||||
PIOS_IRQ_Enable();
|
||||
}
|
||||
|
||||
static void PIOS_USB_HID_TxStart(uint32_t usbhid_id, __attribute__((unused)) uint16_t tx_bytes_avail)
|
||||
{
|
||||
struct pios_usb_hid_dev *usb_hid_dev = (struct pios_usb_hid_dev *)usbhid_id;
|
||||
|
||||
bool valid = PIOS_USB_HID_validate(usb_hid_dev);
|
||||
|
||||
PIOS_Assert(valid);
|
||||
|
||||
if (!PIOS_USB_CheckAvailable(usb_hid_dev->lower_id)) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (GetEPTxStatus(usb_hid_dev->cfg->data_tx_ep) == EP_TX_VALID) {
|
||||
/* Endpoint is already transmitting */
|
||||
return;
|
||||
}
|
||||
|
||||
PIOS_USB_HID_SendReport(usb_hid_dev);
|
||||
}
|
||||
|
||||
static void PIOS_USB_HID_RegisterRxCallback(uint32_t usbhid_id, pios_com_callback rx_in_cb, uint32_t context)
|
||||
{
|
||||
struct pios_usb_hid_dev *usb_hid_dev = (struct pios_usb_hid_dev *)usbhid_id;
|
||||
|
||||
bool valid = PIOS_USB_HID_validate(usb_hid_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
|
||||
*/
|
||||
usb_hid_dev->rx_in_context = context;
|
||||
usb_hid_dev->rx_in_cb = rx_in_cb;
|
||||
}
|
||||
|
||||
static void PIOS_USB_HID_RegisterTxCallback(uint32_t usbhid_id, pios_com_callback tx_out_cb, uint32_t context)
|
||||
{
|
||||
struct pios_usb_hid_dev *usb_hid_dev = (struct pios_usb_hid_dev *)usbhid_id;
|
||||
|
||||
bool valid = PIOS_USB_HID_validate(usb_hid_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
|
||||
*/
|
||||
usb_hid_dev->tx_out_context = context;
|
||||
usb_hid_dev->tx_out_cb = tx_out_cb;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Callback used to indicate a transmission from device INto host completed
|
||||
* Checks if any data remains, pads it into HID packet and sends.
|
||||
*/
|
||||
static void PIOS_USB_HID_EP_IN_Callback(void)
|
||||
{
|
||||
struct pios_usb_hid_dev *usb_hid_dev = (struct pios_usb_hid_dev *)pios_usb_hid_id;
|
||||
|
||||
bool valid = PIOS_USB_HID_validate(usb_hid_dev);
|
||||
|
||||
PIOS_Assert(valid);
|
||||
|
||||
if (!PIOS_USB_CheckAvailable(usb_hid_dev->lower_id)) {
|
||||
return;
|
||||
}
|
||||
|
||||
PIOS_USB_HID_SendReport(usb_hid_dev);
|
||||
}
|
||||
|
||||
/**
|
||||
* EP1 OUT Callback Routine
|
||||
*/
|
||||
static void PIOS_USB_HID_EP_OUT_Callback(void)
|
||||
{
|
||||
struct pios_usb_hid_dev *usb_hid_dev = (struct pios_usb_hid_dev *)pios_usb_hid_id;
|
||||
|
||||
bool valid = PIOS_USB_HID_validate(usb_hid_dev);
|
||||
|
||||
PIOS_Assert(valid);
|
||||
|
||||
uint32_t DataLength;
|
||||
|
||||
/* Read received data (63 bytes) */
|
||||
/* Get the number of received data on the selected Endpoint */
|
||||
DataLength = GetEPRxCount(usb_hid_dev->cfg->data_rx_ep);
|
||||
if (DataLength > sizeof(usb_hid_dev->rx_packet_buffer)) {
|
||||
DataLength = sizeof(usb_hid_dev->rx_packet_buffer);
|
||||
}
|
||||
|
||||
/* Use the memory interface function to read from the selected endpoint */
|
||||
PMAToUserBufferCopy((uint8_t *)usb_hid_dev->rx_packet_buffer,
|
||||
GetEPRxAddr(usb_hid_dev->cfg->data_rx_ep),
|
||||
DataLength);
|
||||
|
||||
if (!usb_hid_dev->rx_in_cb) {
|
||||
/* No Rx call back registered, disable the receiver */
|
||||
SetEPRxStatus(usb_hid_dev->cfg->data_rx_ep, EP_RX_NAK);
|
||||
return;
|
||||
}
|
||||
|
||||
/* The first byte is report ID (not checked), the second byte is the valid data length */
|
||||
uint16_t headroom;
|
||||
bool need_yield = false;
|
||||
#ifdef PIOS_USB_BOARD_BL_HID_HAS_NO_LENGTH_BYTE
|
||||
(usb_hid_dev->rx_in_cb)(usb_hid_dev->rx_in_context,
|
||||
&usb_hid_dev->rx_packet_buffer[1],
|
||||
sizeof(usb_hid_dev->rx_packet_buffer) - 1,
|
||||
&headroom,
|
||||
&need_yield);
|
||||
#else
|
||||
(usb_hid_dev->rx_in_cb)(usb_hid_dev->rx_in_context,
|
||||
&usb_hid_dev->rx_packet_buffer[2],
|
||||
usb_hid_dev->rx_packet_buffer[1],
|
||||
&headroom,
|
||||
&need_yield);
|
||||
#endif
|
||||
|
||||
#ifdef PIOS_USB_BOARD_BL_HID_HAS_NO_LENGTH_BYTE
|
||||
uint16_t max_payload_length = PIOS_USB_BOARD_HID_DATA_LENGTH - 1;
|
||||
#else
|
||||
uint16_t max_payload_length = PIOS_USB_BOARD_HID_DATA_LENGTH - 2;
|
||||
#endif
|
||||
|
||||
if (headroom >= max_payload_length) {
|
||||
/* We have room for a maximum length message */
|
||||
SetEPRxStatus(usb_hid_dev->cfg->data_rx_ep, EP_RX_VALID);
|
||||
} else {
|
||||
/* Not enough room left for a message, apply backpressure */
|
||||
SetEPRxStatus(usb_hid_dev->cfg->data_rx_ep, EP_RX_NAK);
|
||||
}
|
||||
}
|
||||
|
||||
static uint32_t PIOS_USB_HID_Available(uint32_t usbhid_id)
|
||||
{
|
||||
return PIOS_USB_CheckAvailable(usbhid_id) ? COM_AVAILABLE_RXTX : COM_AVAILABLE_NONE;
|
||||
}
|
||||
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB_HID */
|
336
flight/pios/stm32f30x/pios_usb_hid_istr.c
Normal file
336
flight/pios/stm32f30x/pios_usb_hid_istr.c
Normal file
@ -0,0 +1,336 @@
|
||||
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
|
||||
* File Name : usb_istr.c
|
||||
* Author : MCD Application Team
|
||||
* Version : V3.2.1
|
||||
* Date : 07/05/2010
|
||||
* Description : ISTR events interrupt service routines
|
||||
********************************************************************************
|
||||
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
|
||||
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
|
||||
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
|
||||
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
|
||||
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
|
||||
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
|
||||
*******************************************************************************/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "pios.h"
|
||||
|
||||
#ifdef PIOS_INCLUDE_USB
|
||||
|
||||
#include "usb_lib.h"
|
||||
#include "pios_usb_hid_pwr.h"
|
||||
#include "pios_usb_hid_istr.h"
|
||||
#include "pios_usb_hid.h"
|
||||
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
/* Private define ------------------------------------------------------------*/
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
__IO uint16_t wIstr; /* ISTR register last read value */
|
||||
__IO uint8_t bIntPackSOF = 0; /* SOFs received between 2 consecutive packets */
|
||||
|
||||
/* Extern variables ----------------------------------------------------------*/
|
||||
/* Private function prototypes -----------------------------------------------*/
|
||||
/* Private functions ---------------------------------------------------------*/
|
||||
/* function pointers to non-control endpoints service routines */
|
||||
void(*pEpInt_IN[7]) (void) = {
|
||||
EP1_IN_Callback, EP2_IN_Callback, EP3_IN_Callback, EP4_IN_Callback, EP5_IN_Callback, EP6_IN_Callback, EP7_IN_Callback,
|
||||
};
|
||||
|
||||
void(*pEpInt_OUT[7]) (void) = {
|
||||
EP1_OUT_Callback, EP2_OUT_Callback, EP3_OUT_Callback, EP4_OUT_Callback, EP5_OUT_Callback, EP6_OUT_Callback, EP7_OUT_Callback,
|
||||
};
|
||||
|
||||
#ifndef STM32F10X_CL
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : USB_Istr
|
||||
* Description : STR events interrupt service routine
|
||||
* Input :
|
||||
* Output :
|
||||
* Return :
|
||||
*******************************************************************************/
|
||||
void USB_LP_CAN1_RX0_IRQHandler(void) // USB_Istr(void)
|
||||
{
|
||||
wIstr = _GetISTR();
|
||||
|
||||
#if (IMR_MSK & ISTR_CTR)
|
||||
if (wIstr & ISTR_CTR & wInterrupt_Mask) {
|
||||
/* servicing of the endpoint correct transfer interrupt */
|
||||
/* clear of the CTR flag into the sub */
|
||||
CTR_LP();
|
||||
#ifdef CTR_CALLBACK
|
||||
CTR_Callback();
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
|
||||
#if (IMR_MSK & ISTR_RESET)
|
||||
if (wIstr & ISTR_RESET & wInterrupt_Mask) {
|
||||
_SetISTR((uint16_t)CLR_RESET);
|
||||
Device_Property.Reset();
|
||||
#ifdef RESET_CALLBACK
|
||||
RESET_Callback();
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
|
||||
#if (IMR_MSK & ISTR_DOVR)
|
||||
if (wIstr & ISTR_DOVR & wInterrupt_Mask) {
|
||||
_SetISTR((uint16_t)CLR_DOVR);
|
||||
#ifdef DOVR_CALLBACK
|
||||
DOVR_Callback();
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
|
||||
#if (IMR_MSK & ISTR_ERR)
|
||||
if (wIstr & ISTR_ERR & wInterrupt_Mask) {
|
||||
_SetISTR((uint16_t)CLR_ERR);
|
||||
#ifdef ERR_CALLBACK
|
||||
ERR_Callback();
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
|
||||
#if (IMR_MSK & ISTR_WKUP)
|
||||
if (wIstr & ISTR_WKUP & wInterrupt_Mask) {
|
||||
_SetISTR((uint16_t)CLR_WKUP);
|
||||
Resume(RESUME_EXTERNAL);
|
||||
#ifdef WKUP_CALLBACK
|
||||
WKUP_Callback();
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
|
||||
#if (IMR_MSK & ISTR_SUSP)
|
||||
if (wIstr & ISTR_SUSP & wInterrupt_Mask) {
|
||||
/* check if SUSPEND is possible */
|
||||
if (fSuspendEnabled) {
|
||||
Suspend();
|
||||
} else {
|
||||
/* if not possible then resume after xx ms */
|
||||
Resume(RESUME_LATER);
|
||||
}
|
||||
/* clear of the ISTR bit must be done after setting of CNTR_FSUSP */
|
||||
_SetISTR((uint16_t)CLR_SUSP);
|
||||
#ifdef SUSP_CALLBACK
|
||||
SUSP_Callback();
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
|
||||
#if (IMR_MSK & ISTR_SOF)
|
||||
if (wIstr & ISTR_SOF & wInterrupt_Mask) {
|
||||
_SetISTR((uint16_t)CLR_SOF);
|
||||
bIntPackSOF++;
|
||||
|
||||
#ifdef SOF_CALLBACK
|
||||
SOF_Callback();
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
|
||||
#if (IMR_MSK & ISTR_ESOF)
|
||||
if (wIstr & ISTR_ESOF & wInterrupt_Mask) {
|
||||
_SetISTR((uint16_t)CLR_ESOF);
|
||||
/* resume handling timing is made with ESOFs */
|
||||
Resume(RESUME_ESOF); /* request without change of the machine state */
|
||||
|
||||
#ifdef ESOF_CALLBACK
|
||||
ESOF_Callback();
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
} /* USB_Istr */
|
||||
|
||||
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
|
||||
#else /* STM32F10X_CL */
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : STM32_PCD_OTG_ISR_Handler
|
||||
* Description : Handles all USB Device Interrupts
|
||||
* Input : None
|
||||
* Output : None
|
||||
* Return : status
|
||||
*******************************************************************************/
|
||||
u32 STM32_PCD_OTG_ISR_Handler(void)
|
||||
{
|
||||
USB_OTG_GINTSTS_TypeDef gintr_status;
|
||||
u32 retval = 0;
|
||||
|
||||
if (USBD_FS_IsDeviceMode()) { /* ensure that we are in device mode */
|
||||
gintr_status.d32 = OTGD_FS_ReadCoreItr();
|
||||
|
||||
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
|
||||
|
||||
/* If there is no interrupt pending exit the interrupt routine */
|
||||
if (!gintr_status.d32) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
|
||||
/* Early Suspend interrupt */
|
||||
#ifdef INTR_ERLYSUSPEND
|
||||
if (gintr_status.b.erlysuspend) {
|
||||
retval |= OTGD_FS_Handle_EarlySuspend_ISR();
|
||||
}
|
||||
#endif /* INTR_ERLYSUSPEND */
|
||||
|
||||
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
|
||||
/* End of Periodic Frame interrupt */
|
||||
#ifdef INTR_EOPFRAME
|
||||
if (gintr_status.b.eopframe) {
|
||||
retval |= OTGD_FS_Handle_EOPF_ISR();
|
||||
}
|
||||
#endif /* INTR_EOPFRAME */
|
||||
|
||||
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
|
||||
/* Non Periodic Tx FIFO Emty interrupt */
|
||||
#ifdef INTR_NPTXFEMPTY
|
||||
if (gintr_status.b.nptxfempty) {
|
||||
retval |= OTGD_FS_Handle_NPTxFE_ISR();
|
||||
}
|
||||
#endif /* INTR_NPTXFEMPTY */
|
||||
|
||||
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
|
||||
/* Wakeup or RemoteWakeup interrupt */
|
||||
#ifdef INTR_WKUPINTR
|
||||
if (gintr_status.b.wkupintr) {
|
||||
retval |= OTGD_FS_Handle_Wakeup_ISR();
|
||||
}
|
||||
#endif /* INTR_WKUPINTR */
|
||||
|
||||
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
|
||||
/* Suspend interrupt */
|
||||
#ifdef INTR_USBSUSPEND
|
||||
if (gintr_status.b.usbsuspend) {
|
||||
/* check if SUSPEND is possible */
|
||||
if (fSuspendEnabled) {
|
||||
Suspend();
|
||||
} else {
|
||||
/* if not possible then resume after xx ms */
|
||||
Resume(RESUME_LATER); /* This case shouldn't happen in OTG Device mode because
|
||||
there's no ESOF interrupt to increment the ResumeS.bESOFcnt in the Resume state machine */
|
||||
}
|
||||
|
||||
retval |= OTGD_FS_Handle_USBSuspend_ISR();
|
||||
}
|
||||
#endif /* INTR_USBSUSPEND */
|
||||
|
||||
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
|
||||
/* Start of Frame interrupt */
|
||||
#ifdef INTR_SOFINTR
|
||||
if (gintr_status.b.sofintr) {
|
||||
/* Update the frame number variable */
|
||||
bIntPackSOF++;
|
||||
|
||||
retval |= OTGD_FS_Handle_Sof_ISR();
|
||||
}
|
||||
#endif /* INTR_SOFINTR */
|
||||
|
||||
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
|
||||
/* Receive FIFO Queue Status Level interrupt */
|
||||
#ifdef INTR_RXSTSQLVL
|
||||
if (gintr_status.b.rxstsqlvl) {
|
||||
retval |= OTGD_FS_Handle_RxStatusQueueLevel_ISR();
|
||||
}
|
||||
#endif /* INTR_RXSTSQLVL */
|
||||
|
||||
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
|
||||
/* Enumeration Done interrupt */
|
||||
#ifdef INTR_ENUMDONE
|
||||
if (gintr_status.b.enumdone) {
|
||||
retval |= OTGD_FS_Handle_EnumDone_ISR();
|
||||
}
|
||||
#endif /* INTR_ENUMDONE */
|
||||
|
||||
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
|
||||
/* Reset interrutp */
|
||||
#ifdef INTR_USBRESET
|
||||
if (gintr_status.b.usbreset) {
|
||||
retval |= OTGD_FS_Handle_UsbReset_ISR();
|
||||
}
|
||||
#endif /* INTR_USBRESET */
|
||||
|
||||
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
|
||||
/* IN Endpoint interrupt */
|
||||
#ifdef INTR_INEPINTR
|
||||
if (gintr_status.b.inepint) {
|
||||
retval |= OTGD_FS_Handle_InEP_ISR();
|
||||
}
|
||||
#endif /* INTR_INEPINTR */
|
||||
|
||||
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
|
||||
/* OUT Endpoint interrupt */
|
||||
#ifdef INTR_OUTEPINTR
|
||||
if (gintr_status.b.outepintr) {
|
||||
retval |= OTGD_FS_Handle_OutEP_ISR();
|
||||
}
|
||||
#endif /* INTR_OUTEPINTR */
|
||||
|
||||
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
|
||||
/* Mode Mismatch interrupt */
|
||||
#ifdef INTR_MODEMISMATCH
|
||||
if (gintr_status.b.modemismatch) {
|
||||
retval |= OTGD_FS_Handle_ModeMismatch_ISR();
|
||||
}
|
||||
#endif /* INTR_MODEMISMATCH */
|
||||
|
||||
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
|
||||
/* Global IN Endpoints NAK Effective interrupt */
|
||||
#ifdef INTR_GINNAKEFF
|
||||
if (gintr_status.b.ginnakeff) {
|
||||
retval |= OTGD_FS_Handle_GInNakEff_ISR();
|
||||
}
|
||||
#endif /* INTR_GINNAKEFF */
|
||||
|
||||
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
|
||||
/* Global OUT Endpoints NAK effective interrupt */
|
||||
#ifdef INTR_GOUTNAKEFF
|
||||
if (gintr_status.b.goutnakeff) {
|
||||
retval |= OTGD_FS_Handle_GOutNakEff_ISR();
|
||||
}
|
||||
#endif /* INTR_GOUTNAKEFF */
|
||||
|
||||
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
|
||||
/* Isochrounous Out packet Dropped interrupt */
|
||||
#ifdef INTR_ISOOUTDROP
|
||||
if (gintr_status.b.isooutdrop) {
|
||||
retval |= OTGD_FS_Handle_IsoOutDrop_ISR();
|
||||
}
|
||||
#endif /* INTR_ISOOUTDROP */
|
||||
|
||||
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
|
||||
/* Endpoint Mismatch error interrupt */
|
||||
#ifdef INTR_EPMISMATCH
|
||||
if (gintr_status.b.epmismatch) {
|
||||
retval |= OTGD_FS_Handle_EPMismatch_ISR();
|
||||
}
|
||||
#endif /* INTR_EPMISMATCH */
|
||||
|
||||
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
|
||||
/* Incomplete Isochrous IN tranfer error interrupt */
|
||||
#ifdef INTR_INCOMPLISOIN
|
||||
if (gintr_status.b.incomplisoin) {
|
||||
retval |= OTGD_FS_Handle_IncomplIsoIn_ISR();
|
||||
}
|
||||
#endif /* INTR_INCOMPLISOIN */
|
||||
|
||||
/*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*-*/
|
||||
/* Incomplete Isochrous OUT tranfer error interrupt */
|
||||
#ifdef INTR_INCOMPLISOOUT
|
||||
if (gintr_status.b.outepintr) {
|
||||
retval |= OTGD_FS_Handle_IncomplIsoOut_ISR();
|
||||
}
|
||||
#endif /* INTR_INCOMPLISOOUT */
|
||||
}
|
||||
return retval;
|
||||
}
|
||||
|
||||
#endif /* STM32F10X_CL */
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
|
||||
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/
|
292
flight/pios/stm32f30x/pios_usb_hid_pwr.c
Normal file
292
flight/pios/stm32f30x/pios_usb_hid_pwr.c
Normal file
@ -0,0 +1,292 @@
|
||||
/******************** (C) COPYRIGHT 2010 STMicroelectronics ********************
|
||||
* File Name : usb_pwr.c
|
||||
* Author : MCD Application Team
|
||||
* Version : V3.2.1
|
||||
* Date : 07/05/2010
|
||||
* Description : Connection/disconnection & power management
|
||||
********************************************************************************
|
||||
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
|
||||
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
|
||||
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
|
||||
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
|
||||
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
|
||||
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
|
||||
*******************************************************************************/
|
||||
|
||||
/* Includes ------------------------------------------------------------------*/
|
||||
#include "pios.h"
|
||||
#include "stm32f30x.h"
|
||||
#include "usb_lib.h"
|
||||
#include "usb_conf.h"
|
||||
#include "pios_usb_hid_pwr.h"
|
||||
#include "pios_usb_hid.h"
|
||||
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
/* Private define ------------------------------------------------------------*/
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
__IO uint32_t bDeviceState = UNCONNECTED; /* USB device status */
|
||||
__IO bool fSuspendEnabled = true; /* true when suspend is possible */
|
||||
|
||||
struct {
|
||||
__IO RESUME_STATE eState;
|
||||
__IO uint8_t bESOFcnt;
|
||||
} ResumeS;
|
||||
|
||||
/* Extern variables ----------------------------------------------------------*/
|
||||
/* Private function prototypes -----------------------------------------------*/
|
||||
/* Extern function prototypes ------------------------------------------------*/
|
||||
/* Private functions ---------------------------------------------------------*/
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : USB_Cable_Config.
|
||||
* Description : Software Connection/Disconnection of USB Cable.
|
||||
* Input : NewState: new state.
|
||||
* Output : None.
|
||||
* Return : None
|
||||
*******************************************************************************/
|
||||
void USB_Cable_Config(FunctionalState __attribute__((unused)) NewState)
|
||||
{}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : PowerOn
|
||||
* Description :
|
||||
* Input : None.
|
||||
* Output : None.
|
||||
* Return : USB_SUCCESS.
|
||||
*******************************************************************************/
|
||||
RESULT PowerOn(void)
|
||||
{
|
||||
#ifndef STM32F10X_CL
|
||||
uint16_t wRegVal;
|
||||
|
||||
/*** cable plugged-in ? ***/
|
||||
USB_Cable_Config(ENABLE);
|
||||
|
||||
/*** CNTR_PWDN = 0 ***/
|
||||
wRegVal = CNTR_FRES;
|
||||
_SetCNTR(wRegVal);
|
||||
|
||||
/*** CNTR_FRES = 0 ***/
|
||||
wInterrupt_Mask = 0;
|
||||
_SetCNTR(wInterrupt_Mask);
|
||||
/*** Clear pending interrupts ***/
|
||||
_SetISTR(0);
|
||||
/*** Set interrupt mask ***/
|
||||
wInterrupt_Mask = CNTR_RESETM | CNTR_SUSPM | CNTR_WKUPM;
|
||||
_SetCNTR(wInterrupt_Mask);
|
||||
#endif /* STM32F10X_CL */
|
||||
|
||||
return USB_SUCCESS;
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : PowerOff
|
||||
* Description : handles switch-off conditions
|
||||
* Input : None.
|
||||
* Output : None.
|
||||
* Return : USB_SUCCESS.
|
||||
*******************************************************************************/
|
||||
RESULT PowerOff()
|
||||
{
|
||||
#ifndef STM32F10X_CL
|
||||
/* disable all ints and force USB reset */
|
||||
_SetCNTR(CNTR_FRES);
|
||||
/* clear interrupt status register */
|
||||
_SetISTR(0);
|
||||
/* Disable the Pull-Up */
|
||||
USB_Cable_Config(DISABLE);
|
||||
/* switch-off device */
|
||||
_SetCNTR(CNTR_FRES + CNTR_PDWN);
|
||||
#endif /* STM32F10X_CL */
|
||||
|
||||
/* sw variables reset */
|
||||
/* ... */
|
||||
|
||||
return USB_SUCCESS;
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : Enter_LowPowerMode.
|
||||
* Description : Power-off system clocks and power while entering suspend mode.
|
||||
* Input : None.
|
||||
* Output : None.
|
||||
* Return : None.
|
||||
*******************************************************************************/
|
||||
void Enter_LowPowerMode(void)
|
||||
{
|
||||
/* Set the device state to suspend */
|
||||
bDeviceState = SUSPENDED;
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : Suspend
|
||||
* Description : sets suspend mode operating conditions
|
||||
* Input : None.
|
||||
* Output : None.
|
||||
* Return : USB_SUCCESS.
|
||||
*******************************************************************************/
|
||||
void Suspend(void)
|
||||
{
|
||||
#ifndef STM32F10X_CL
|
||||
uint16_t wCNTR;
|
||||
/* suspend preparation */
|
||||
/* ... */
|
||||
|
||||
/* macrocell enters suspend mode */
|
||||
wCNTR = _GetCNTR();
|
||||
wCNTR |= CNTR_FSUSP;
|
||||
_SetCNTR(wCNTR);
|
||||
#endif /* STM32F10X_CL */
|
||||
|
||||
/* ------------------ ONLY WITH BUS-POWERED DEVICES ---------------------- */
|
||||
/* power reduction */
|
||||
/* ... on connected devices */
|
||||
|
||||
#ifndef STM32F10X_CL
|
||||
/* force low-power mode in the macrocell */
|
||||
wCNTR = _GetCNTR();
|
||||
wCNTR |= CNTR_LPMODE;
|
||||
_SetCNTR(wCNTR);
|
||||
#endif /* STM32F10X_CL */
|
||||
|
||||
/* switch-off the clocks */
|
||||
/* ... */
|
||||
Enter_LowPowerMode();
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : Leave_LowPowerMode.
|
||||
* Description : Restores system clocks and power while exiting suspend mode.
|
||||
* Input : None.
|
||||
* Output : None.
|
||||
* Return : None.
|
||||
*******************************************************************************/
|
||||
void Leave_LowPowerMode(void)
|
||||
{
|
||||
DEVICE_INFO *pInfo = &Device_Info;
|
||||
|
||||
/* Set the device state to the correct state */
|
||||
if (pInfo->Current_Configuration != 0) {
|
||||
/* Device configured */
|
||||
bDeviceState = CONFIGURED;
|
||||
} else {
|
||||
bDeviceState = ATTACHED;
|
||||
}
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : Resume_Init
|
||||
* Description : Handles wake-up restoring normal operations
|
||||
* Input : None.
|
||||
* Output : None.
|
||||
* Return : USB_SUCCESS.
|
||||
*******************************************************************************/
|
||||
void Resume_Init(void)
|
||||
{
|
||||
#ifndef STM32F10X_CL
|
||||
uint16_t wCNTR;
|
||||
#endif /* STM32F10X_CL */
|
||||
|
||||
/* ------------------ ONLY WITH BUS-POWERED DEVICES ---------------------- */
|
||||
/* restart the clocks */
|
||||
/* ... */
|
||||
|
||||
#ifndef STM32F10X_CL
|
||||
/* CNTR_LPMODE = 0 */
|
||||
wCNTR = _GetCNTR();
|
||||
wCNTR &= (~CNTR_LPMODE);
|
||||
_SetCNTR(wCNTR);
|
||||
#endif /* STM32F10X_CL */
|
||||
|
||||
/* restore full power */
|
||||
/* ... on connected devices */
|
||||
Leave_LowPowerMode();
|
||||
|
||||
#ifndef STM32F10X_CL
|
||||
/* reset FSUSP bit */
|
||||
_SetCNTR(IMR_MSK);
|
||||
#endif /* STM32F10X_CL */
|
||||
|
||||
/* reverse suspend preparation */
|
||||
/* ... */
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : Resume
|
||||
* Description : This is the state machine handling resume operations and
|
||||
* timing sequence. The control is based on the Resume structure
|
||||
* variables and on the ESOF interrupt calling this subroutine
|
||||
* without changing machine state.
|
||||
* Input : a state machine value (RESUME_STATE)
|
||||
* RESUME_ESOF doesn't change ResumeS.eState allowing
|
||||
* decrementing of the ESOF counter in different states.
|
||||
* Output : None.
|
||||
* Return : None.
|
||||
*******************************************************************************/
|
||||
void Resume(RESUME_STATE eResumeSetVal)
|
||||
{
|
||||
#ifndef STM32F10X_CL
|
||||
uint16_t wCNTR;
|
||||
#endif /* STM32F10X_CL */
|
||||
|
||||
if (eResumeSetVal != RESUME_ESOF) {
|
||||
ResumeS.eState = eResumeSetVal;
|
||||
}
|
||||
|
||||
switch (ResumeS.eState) {
|
||||
case RESUME_EXTERNAL:
|
||||
Resume_Init();
|
||||
ResumeS.eState = RESUME_OFF;
|
||||
break;
|
||||
case RESUME_INTERNAL:
|
||||
Resume_Init();
|
||||
ResumeS.eState = RESUME_START;
|
||||
break;
|
||||
case RESUME_LATER:
|
||||
ResumeS.bESOFcnt = 2;
|
||||
ResumeS.eState = RESUME_WAIT;
|
||||
break;
|
||||
case RESUME_WAIT:
|
||||
ResumeS.bESOFcnt--;
|
||||
if (ResumeS.bESOFcnt == 0) {
|
||||
ResumeS.eState = RESUME_START;
|
||||
}
|
||||
break;
|
||||
case RESUME_START:
|
||||
#ifdef STM32F10X_CL
|
||||
OTGD_FS_SetRemoteWakeup();
|
||||
#else
|
||||
wCNTR = _GetCNTR();
|
||||
wCNTR |= CNTR_RESUME;
|
||||
_SetCNTR(wCNTR);
|
||||
#endif /* STM32F10X_CL */
|
||||
ResumeS.eState = RESUME_ON;
|
||||
ResumeS.bESOFcnt = 10;
|
||||
break;
|
||||
case RESUME_ON:
|
||||
#ifndef STM32F10X_CL
|
||||
ResumeS.bESOFcnt--;
|
||||
if (ResumeS.bESOFcnt == 0) {
|
||||
#endif /* STM32F10X_CL */
|
||||
#ifdef STM32F10X_CL
|
||||
OTGD_FS_ResetRemoteWakeup();
|
||||
#else
|
||||
wCNTR = _GetCNTR();
|
||||
wCNTR &= (~CNTR_RESUME);
|
||||
_SetCNTR(wCNTR);
|
||||
#endif /* STM32F10X_CL */
|
||||
ResumeS.eState = RESUME_OFF;
|
||||
#ifndef STM32F10X_CL
|
||||
}
|
||||
#endif /* STM32F10X_CL */
|
||||
break;
|
||||
case RESUME_OFF:
|
||||
case RESUME_ESOF:
|
||||
default:
|
||||
ResumeS.eState = RESUME_OFF;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/
|
572
flight/pios/stm32f30x/pios_usbhook.c
Normal file
572
flight/pios/stm32f30x/pios_usbhook.c
Normal file
@ -0,0 +1,572 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_USBHOOK USB glue code
|
||||
* @brief Glue between PiOS and STM32 libs
|
||||
* @{
|
||||
*
|
||||
* @file pios_usbhook.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Glue between PiOS and STM32 libs
|
||||
* @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_USB
|
||||
|
||||
#include "pios_usb.h" /* PIOS_USB_* */
|
||||
#include "pios_usbhook.h"
|
||||
#include "pios_usb_defs.h" /* struct usb_* */
|
||||
#include "pios_usb_hid_pwr.h"
|
||||
#include "pios_usb_cdc_priv.h" /* PIOS_USB_CDC_* */
|
||||
#include "pios_usb_board_data.h" /* PIOS_USB_BOARD_* */
|
||||
|
||||
/* STM32 USB Library Definitions */
|
||||
#include "usb_lib.h"
|
||||
|
||||
static void (*ep0_rxready_cb)(void) = 0;
|
||||
|
||||
static ONE_DESCRIPTOR Device_Descriptor;
|
||||
|
||||
void PIOS_USBHOOK_RegisterDevice(const uint8_t *desc, uint16_t desc_size)
|
||||
{
|
||||
Device_Descriptor.Descriptor = desc;
|
||||
Device_Descriptor.Descriptor_Size = desc_size;
|
||||
}
|
||||
|
||||
static ONE_DESCRIPTOR Config_Descriptor;
|
||||
|
||||
void PIOS_USBHOOK_RegisterConfig(__attribute__((unused)) uint8_t config_id, const uint8_t *desc, uint16_t desc_size)
|
||||
{
|
||||
Config_Descriptor.Descriptor = desc;
|
||||
Config_Descriptor.Descriptor_Size = desc_size;
|
||||
}
|
||||
|
||||
static ONE_DESCRIPTOR String_Descriptor[4];
|
||||
|
||||
void PIOS_USBHOOK_RegisterString(enum usb_string_desc string_id, const uint8_t *desc, uint16_t desc_size)
|
||||
{
|
||||
if (string_id < NELEMENTS(String_Descriptor)) {
|
||||
String_Descriptor[string_id].Descriptor = desc;
|
||||
String_Descriptor[string_id].Descriptor_Size = desc_size;
|
||||
}
|
||||
}
|
||||
|
||||
static ONE_DESCRIPTOR Hid_Descriptor;
|
||||
|
||||
void PIOS_USB_HID_RegisterHidDescriptor(const uint8_t *desc, uint16_t desc_size)
|
||||
{
|
||||
Hid_Descriptor.Descriptor = desc;
|
||||
Hid_Descriptor.Descriptor_Size = desc_size;
|
||||
}
|
||||
|
||||
static ONE_DESCRIPTOR Hid_Report_Descriptor;
|
||||
|
||||
void PIOS_USB_HID_RegisterHidReport(const uint8_t *desc, uint16_t desc_size)
|
||||
{
|
||||
Hid_Report_Descriptor.Descriptor = desc;
|
||||
Hid_Report_Descriptor.Descriptor_Size = desc_size;
|
||||
}
|
||||
|
||||
void PIOS_USBHOOK_Deactivate(void)
|
||||
{}
|
||||
|
||||
#include "stm32f30x.h" /* __IO */
|
||||
__IO uint8_t EXTI_Enable;
|
||||
|
||||
uint32_t ProtocolValue;
|
||||
|
||||
DEVICE Device_Table = {
|
||||
PIOS_USB_BOARD_EP_NUM,
|
||||
1
|
||||
};
|
||||
|
||||
static void PIOS_USBHOOK_Init(void);
|
||||
static void PIOS_USBHOOK_Reset(void);
|
||||
static void PIOS_USBHOOK_Status_In(void);
|
||||
static void PIOS_USBHOOK_Status_Out(void);
|
||||
static RESULT PIOS_USBHOOK_Data_Setup(uint8_t RequestNo);
|
||||
static RESULT PIOS_USBHOOK_NoData_Setup(uint8_t RequestNo);
|
||||
static RESULT PIOS_USBHOOK_Get_Interface_Setting(uint8_t Interface, uint8_t AlternateSetting);
|
||||
static const uint8_t *PIOS_USBHOOK_GetDeviceDescriptor(uint16_t Length);
|
||||
static const uint8_t *PIOS_USBHOOK_GetConfigDescriptor(uint16_t Length);
|
||||
static const uint8_t *PIOS_USBHOOK_GetStringDescriptor(uint16_t Length);
|
||||
|
||||
DEVICE_PROP Device_Property = {
|
||||
.Init = PIOS_USBHOOK_Init,
|
||||
.Reset = PIOS_USBHOOK_Reset,
|
||||
.Process_Status_IN = PIOS_USBHOOK_Status_In,
|
||||
.Process_Status_OUT = PIOS_USBHOOK_Status_Out,
|
||||
.Class_Data_Setup = PIOS_USBHOOK_Data_Setup,
|
||||
.Class_NoData_Setup = PIOS_USBHOOK_NoData_Setup,
|
||||
.Class_Get_Interface_Setting = PIOS_USBHOOK_Get_Interface_Setting,
|
||||
.GetDeviceDescriptor = PIOS_USBHOOK_GetDeviceDescriptor,
|
||||
.GetConfigDescriptor = PIOS_USBHOOK_GetConfigDescriptor,
|
||||
.GetStringDescriptor = PIOS_USBHOOK_GetStringDescriptor,
|
||||
.RxEP_buffer = 0,
|
||||
.MaxPacketSize = 0x40,
|
||||
};
|
||||
|
||||
static void PIOS_USBHOOK_SetConfiguration(void);
|
||||
static void PIOS_USBHOOK_SetDeviceAddress(void);
|
||||
|
||||
USER_STANDARD_REQUESTS User_Standard_Requests = {
|
||||
.User_GetConfiguration = NOP_Process,
|
||||
.User_SetConfiguration = PIOS_USBHOOK_SetConfiguration,
|
||||
.User_GetInterface = NOP_Process,
|
||||
.User_SetInterface = NOP_Process,
|
||||
.User_GetStatus = NOP_Process,
|
||||
.User_ClearFeature = NOP_Process,
|
||||
.User_SetEndPointFeature = NOP_Process,
|
||||
.User_SetDeviceFeature = NOP_Process,
|
||||
.User_SetDeviceAddress = PIOS_USBHOOK_SetDeviceAddress
|
||||
};
|
||||
|
||||
static RESULT PIOS_USBHOOK_SetProtocol(void);
|
||||
static const uint8_t *PIOS_USBHOOK_GetProtocolValue(uint16_t Length);
|
||||
static const uint8_t *PIOS_USBHOOK_GetReportDescriptor(uint16_t Length);
|
||||
static const uint8_t *PIOS_USBHOOK_GetHIDDescriptor(uint16_t Length);
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : PIOS_USBHOOK_Init.
|
||||
* Description : Custom HID init routine.
|
||||
* Input : None.
|
||||
* Output : None.
|
||||
* Return : None.
|
||||
*******************************************************************************/
|
||||
static void PIOS_USBHOOK_Init(void)
|
||||
{
|
||||
pInformation->Current_Configuration = 0;
|
||||
|
||||
/* Connect the device */
|
||||
PowerOn();
|
||||
|
||||
/* Perform basic device initialization operations */
|
||||
USB_SIL_Init();
|
||||
|
||||
bDeviceState = UNCONNECTED;
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : PIOS_USBHOOK_Reset.
|
||||
* Description : Custom HID reset routine.
|
||||
* Input : None.
|
||||
* Output : None.
|
||||
* Return : None.
|
||||
*******************************************************************************/
|
||||
static void PIOS_USBHOOK_Reset(void)
|
||||
{
|
||||
/* Set DEVICE as not configured */
|
||||
pInformation->Current_Configuration = 0;
|
||||
pInformation->Current_Interface = 0; /*the default Interface */
|
||||
|
||||
/* Current Feature initialization */
|
||||
pInformation->Current_Feature = 0;
|
||||
|
||||
#ifdef STM32F10X_CL
|
||||
/* EP0 is already configured in DFU_Init() by USB_SIL_Init() function */
|
||||
|
||||
/* Init EP1 IN as Interrupt endpoint */
|
||||
OTG_DEV_EP_Init(EP1_IN, OTG_DEV_EP_TYPE_INT, 2);
|
||||
|
||||
/* Init EP1 OUT as Interrupt endpoint */
|
||||
OTG_DEV_EP_Init(EP1_OUT, OTG_DEV_EP_TYPE_INT, 2);
|
||||
#else
|
||||
SetBTABLE(BTABLE_ADDRESS);
|
||||
|
||||
/* Initialize Endpoint 0 (Control) */
|
||||
SetEPType(ENDP0, EP_CONTROL);
|
||||
SetEPTxAddr(ENDP0, ENDP0_TXADDR);
|
||||
SetEPTxStatus(ENDP0, EP_TX_STALL);
|
||||
Clear_Status_Out(ENDP0);
|
||||
|
||||
SetEPRxAddr(ENDP0, ENDP0_RXADDR);
|
||||
SetEPRxCount(ENDP0, Device_Property.MaxPacketSize);
|
||||
SetEPRxValid(ENDP0);
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_HID)
|
||||
/* Initialize Endpoint 1 (HID) */
|
||||
SetEPType(ENDP1, EP_INTERRUPT);
|
||||
SetEPTxAddr(ENDP1, ENDP1_TXADDR);
|
||||
SetEPTxCount(ENDP1, PIOS_USB_BOARD_HID_DATA_LENGTH);
|
||||
SetEPTxStatus(ENDP1, EP_TX_NAK);
|
||||
|
||||
SetEPRxAddr(ENDP1, ENDP1_RXADDR);
|
||||
SetEPRxCount(ENDP1, PIOS_USB_BOARD_HID_DATA_LENGTH);
|
||||
SetEPRxStatus(ENDP1, EP_RX_VALID);
|
||||
#endif /* PIOS_INCLUDE_USB_HID */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_CDC)
|
||||
/* Initialize Endpoint 2 (CDC Call Control) */
|
||||
SetEPType(ENDP2, EP_INTERRUPT);
|
||||
SetEPTxAddr(ENDP2, ENDP2_TXADDR);
|
||||
SetEPTxStatus(ENDP2, EP_TX_NAK);
|
||||
|
||||
SetEPRxAddr(ENDP2, ENDP2_RXADDR);
|
||||
SetEPRxCount(ENDP2, PIOS_USB_BOARD_CDC_MGMT_LENGTH);
|
||||
SetEPRxStatus(ENDP2, EP_RX_DIS);
|
||||
|
||||
/* Initialize Endpoint 3 (CDC Data) */
|
||||
SetEPType(ENDP3, EP_BULK);
|
||||
SetEPTxAddr(ENDP3, ENDP3_TXADDR);
|
||||
SetEPTxStatus(ENDP3, EP_TX_NAK);
|
||||
|
||||
SetEPRxAddr(ENDP3, ENDP3_RXADDR);
|
||||
SetEPRxCount(ENDP3, PIOS_USB_BOARD_CDC_DATA_LENGTH);
|
||||
SetEPRxStatus(ENDP3, EP_RX_VALID);
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB_CDC */
|
||||
|
||||
/* Set this device to response on default address */
|
||||
SetDeviceAddress(0);
|
||||
#endif /* STM32F10X_CL */
|
||||
|
||||
bDeviceState = ATTACHED;
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : PIOS_USBHOOK_SetConfiguration.
|
||||
* Description : Update the device state to configured
|
||||
* Input : None.
|
||||
* Output : None.
|
||||
* Return : None.
|
||||
*******************************************************************************/
|
||||
static void PIOS_USBHOOK_SetConfiguration(void)
|
||||
{
|
||||
if (pInformation->Current_Configuration != 0) {
|
||||
/* Device configured */
|
||||
bDeviceState = CONFIGURED;
|
||||
}
|
||||
|
||||
/* Enable transfers */
|
||||
PIOS_USB_ChangeConnectionState(pInformation->Current_Configuration != 0);
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : PIOS_USBHOOK_SetConfiguration.
|
||||
* Description : Update the device state to addressed.
|
||||
* Input : None.
|
||||
* Output : None.
|
||||
* Return : None.
|
||||
*******************************************************************************/
|
||||
static void PIOS_USBHOOK_SetDeviceAddress(void)
|
||||
{
|
||||
bDeviceState = ADDRESSED;
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : PIOS_USBHOOK_Status_In.
|
||||
* Description : status IN routine.
|
||||
* Input : None.
|
||||
* Output : None.
|
||||
* Return : None.
|
||||
*******************************************************************************/
|
||||
static void PIOS_USBHOOK_Status_In(void)
|
||||
{
|
||||
/* this callback gets executed after sending ZLP and doing In0_Process(), to ack */
|
||||
if (ep0_rxready_cb) {
|
||||
ep0_rxready_cb();
|
||||
ep0_rxready_cb = 0;
|
||||
}
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : PIOS_USBHOOK_Status_Out
|
||||
* Description : status OUT routine.
|
||||
* Input : None.
|
||||
* Output : None.
|
||||
* Return : None.
|
||||
*******************************************************************************/
|
||||
static void PIOS_USBHOOK_Status_Out(void)
|
||||
{}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : PIOS_USBHOOK_Data_Setup
|
||||
* Description : Handle the data class specific requests.
|
||||
* Input : Request Nb.
|
||||
* Output : None.
|
||||
* Return : USB_UNSUPPORT or USB_SUCCESS.
|
||||
*******************************************************************************/
|
||||
extern uint8_t *PIOS_USB_CDC_SetLineCoding(uint16_t Length);
|
||||
extern const uint8_t *PIOS_USB_CDC_GetLineCoding(uint16_t Length);
|
||||
extern void PIOS_USB_CDC_SetLineCoding_Completed();
|
||||
|
||||
static RESULT PIOS_USBHOOK_Data_Setup(uint8_t RequestNo)
|
||||
{
|
||||
uint8_t *(*CopyOutRoutine)(uint16_t);
|
||||
const uint8_t *(*CopyInRoutine)(uint16_t);
|
||||
|
||||
CopyInRoutine = NULL;
|
||||
CopyOutRoutine = NULL;
|
||||
|
||||
switch (Type_Recipient) {
|
||||
case (STANDARD_REQUEST | INTERFACE_RECIPIENT):
|
||||
switch (pInformation->USBwIndex0) {
|
||||
#if defined(PIOS_INCLUDE_USB_CDC)
|
||||
case 2: /* HID Interface */
|
||||
#else
|
||||
case 0: /* HID Interface */
|
||||
#endif
|
||||
switch (RequestNo) {
|
||||
case GET_DESCRIPTOR:
|
||||
switch (pInformation->USBwValue1) {
|
||||
case USB_DESC_TYPE_REPORT:
|
||||
CopyInRoutine = PIOS_USBHOOK_GetReportDescriptor;
|
||||
break;
|
||||
case USB_DESC_TYPE_HID:
|
||||
CopyInRoutine = PIOS_USBHOOK_GetHIDDescriptor;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case (CLASS_REQUEST | INTERFACE_RECIPIENT):
|
||||
switch (pInformation->USBwIndex0) {
|
||||
#if defined(PIOS_INCLUDE_USB_CDC)
|
||||
case 2: /* HID Interface */
|
||||
#else
|
||||
case 0: /* HID Interface */
|
||||
#endif
|
||||
switch (RequestNo) {
|
||||
case USB_HID_REQ_GET_PROTOCOL:
|
||||
CopyInRoutine = PIOS_USBHOOK_GetProtocolValue;
|
||||
break;
|
||||
}
|
||||
|
||||
break;
|
||||
#if defined(PIOS_INCLUDE_USB_CDC)
|
||||
case 0: /* CDC Call Control Interface */
|
||||
switch (RequestNo) {
|
||||
case USB_CDC_REQ_SET_LINE_CODING:
|
||||
CopyOutRoutine = PIOS_USB_CDC_SetLineCoding;
|
||||
ep0_rxready_cb = PIOS_USB_CDC_SetLineCoding_Completed;
|
||||
break;
|
||||
case USB_CDC_REQ_GET_LINE_CODING:
|
||||
CopyInRoutine = PIOS_USB_CDC_GetLineCoding;
|
||||
break;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case 1: /* CDC Data Interface */
|
||||
switch (RequestNo) {
|
||||
case 0:
|
||||
break;
|
||||
}
|
||||
|
||||
break;
|
||||
#endif /* PIOS_INCLUDE_USB_CDC */
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
/* No registered copy routine */
|
||||
if ((CopyInRoutine == NULL) && (CopyOutRoutine == NULL)) {
|
||||
return USB_UNSUPPORT;
|
||||
}
|
||||
|
||||
/* Registered copy in AND copy out routine */
|
||||
if ((CopyInRoutine != NULL) && (CopyOutRoutine != NULL)) {
|
||||
/* This should never happen */
|
||||
return USB_UNSUPPORT;
|
||||
}
|
||||
|
||||
if (CopyInRoutine != NULL) {
|
||||
pInformation->Ctrl_Info.CopyData = (typeof(pInformation->Ctrl_Info.CopyData))CopyInRoutine;
|
||||
pInformation->Ctrl_Info.Usb_wOffset = 0;
|
||||
(*CopyInRoutine)(0);
|
||||
} else if (CopyOutRoutine != NULL) {
|
||||
pInformation->Ctrl_Info.CopyData = CopyOutRoutine;
|
||||
pInformation->Ctrl_Info.Usb_rOffset = 0;
|
||||
(*CopyOutRoutine)(0);
|
||||
}
|
||||
|
||||
return USB_SUCCESS;
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : PIOS_USBHOOK_NoData_Setup
|
||||
* Description : handle the no data class specific requests
|
||||
* Input : Request Nb.
|
||||
* Output : None.
|
||||
* Return : USB_UNSUPPORT or USB_SUCCESS.
|
||||
*******************************************************************************/
|
||||
extern RESULT PIOS_USB_CDC_SetControlLineState(void);
|
||||
|
||||
static RESULT PIOS_USBHOOK_NoData_Setup(uint8_t RequestNo)
|
||||
{
|
||||
switch (Type_Recipient) {
|
||||
case (CLASS_REQUEST | INTERFACE_RECIPIENT):
|
||||
switch (pInformation->USBwIndex0) {
|
||||
#if defined(PIOS_INCLUDE_USB_CDC)
|
||||
case 2: /* HID */
|
||||
#else
|
||||
case 0: /* HID */
|
||||
#endif
|
||||
switch (RequestNo) {
|
||||
case USB_HID_REQ_SET_PROTOCOL:
|
||||
return PIOS_USBHOOK_SetProtocol();
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_CDC)
|
||||
case 0: /* CDC Call Control Interface */
|
||||
switch (RequestNo) {
|
||||
case USB_CDC_REQ_SET_CONTROL_LINE_STATE:
|
||||
return PIOS_USB_CDC_SetControlLineState();
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
break;
|
||||
#endif /* PIOS_INCLUDE_USB_CDC */
|
||||
}
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
return USB_UNSUPPORT;
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : PIOS_USBHOOK_GetDeviceDescriptor.
|
||||
* Description : Gets the device descriptor.
|
||||
* Input : Length
|
||||
* Output : None.
|
||||
* Return : The address of the device descriptor.
|
||||
*******************************************************************************/
|
||||
static const uint8_t *PIOS_USBHOOK_GetDeviceDescriptor(uint16_t Length)
|
||||
{
|
||||
return Standard_GetDescriptorData(Length, &Device_Descriptor);
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : PIOS_USBHOOK_GetConfigDescriptor.
|
||||
* Description : Gets the configuration descriptor.
|
||||
* Input : Length
|
||||
* Output : None.
|
||||
* Return : The address of the configuration descriptor.
|
||||
*******************************************************************************/
|
||||
static const uint8_t *PIOS_USBHOOK_GetConfigDescriptor(uint16_t Length)
|
||||
{
|
||||
return Standard_GetDescriptorData(Length, &Config_Descriptor);
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : PIOS_USBHOOK_GetStringDescriptor
|
||||
* Description : Gets the string descriptors according to the needed index
|
||||
* Input : Length
|
||||
* Output : None.
|
||||
* Return : The address of the string descriptors.
|
||||
*******************************************************************************/
|
||||
static const uint8_t *PIOS_USBHOOK_GetStringDescriptor(uint16_t Length)
|
||||
{
|
||||
uint8_t wValue0 = pInformation->USBwValue0;
|
||||
|
||||
if (wValue0 > 4) {
|
||||
return NULL;
|
||||
} else {
|
||||
return Standard_GetDescriptorData(Length, &String_Descriptor[wValue0]);
|
||||
}
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : PIOS_USBHOOK_GetReportDescriptor.
|
||||
* Description : Gets the HID report descriptor.
|
||||
* Input : Length
|
||||
* Output : None.
|
||||
* Return : The address of the configuration descriptor.
|
||||
*******************************************************************************/
|
||||
static const uint8_t *PIOS_USBHOOK_GetReportDescriptor(uint16_t Length)
|
||||
{
|
||||
return Standard_GetDescriptorData(Length, &Hid_Report_Descriptor);
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : PIOS_USBHOOK_GetHIDDescriptor.
|
||||
* Description : Gets the HID descriptor.
|
||||
* Input : Length
|
||||
* Output : None.
|
||||
* Return : The address of the configuration descriptor.
|
||||
*******************************************************************************/
|
||||
static const uint8_t *PIOS_USBHOOK_GetHIDDescriptor(uint16_t Length)
|
||||
{
|
||||
return Standard_GetDescriptorData(Length, &Hid_Descriptor);
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : PIOS_USBHOOK_Get_Interface_Setting.
|
||||
* Description : tests the interface and the alternate setting according to the
|
||||
* supported one.
|
||||
* Input : - Interface : interface number.
|
||||
* - AlternateSetting : Alternate Setting number.
|
||||
* Output : None.
|
||||
* Return : USB_SUCCESS or USB_UNSUPPORT.
|
||||
*******************************************************************************/
|
||||
static RESULT PIOS_USBHOOK_Get_Interface_Setting(uint8_t Interface, uint8_t AlternateSetting)
|
||||
{
|
||||
if (AlternateSetting > 0) {
|
||||
return USB_UNSUPPORT;
|
||||
} else if (Interface > 0) {
|
||||
return USB_UNSUPPORT;
|
||||
}
|
||||
return USB_SUCCESS;
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : PIOS_USBHOOK_SetProtocol
|
||||
* Description : Set Protocol request routine.
|
||||
* Input : None.
|
||||
* Output : None.
|
||||
* Return : USB SUCCESS.
|
||||
*******************************************************************************/
|
||||
static RESULT PIOS_USBHOOK_SetProtocol(void)
|
||||
{
|
||||
uint8_t wValue0 = pInformation->USBwValue0;
|
||||
|
||||
ProtocolValue = wValue0;
|
||||
return USB_SUCCESS;
|
||||
}
|
||||
|
||||
/*******************************************************************************
|
||||
* Function Name : PIOS_USBHOOK_GetProtocolValue
|
||||
* Description : get the protocol value
|
||||
* Input : Length.
|
||||
* Output : None.
|
||||
* Return : address of the protcol value.
|
||||
*******************************************************************************/
|
||||
static const uint8_t *PIOS_USBHOOK_GetProtocolValue(uint16_t Length)
|
||||
{
|
||||
if (Length == 0) {
|
||||
pInformation->Ctrl_Info.Usb_wLength = 1;
|
||||
return NULL;
|
||||
} else {
|
||||
return (uint8_t *)(&ProtocolValue);
|
||||
}
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
|
||||
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/
|
186
flight/pios/stm32f30x/pios_wdg.c
Normal file
186
flight/pios/stm32f30x/pios_wdg.c
Normal file
@ -0,0 +1,186 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_WDG Watchdog Functions
|
||||
* @brief PIOS Comamnds to initialize and clear watchdog timer
|
||||
* @{
|
||||
*
|
||||
* @file pios_spi.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
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @notes
|
||||
*
|
||||
* The PIOS Watchdog provides a HAL to initialize a watchdog
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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
|
||||
*/
|
||||
|
||||
/*
|
||||
* @todo This is virtually identical to the F1xx code and should be merged.
|
||||
*/
|
||||
|
||||
#include "pios.h"
|
||||
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
|
||||
#include "stm32f30x_iwdg.h"
|
||||
#include "stm32f30x_dbgmcu.h"
|
||||
#include "stm32f30x_rtc.h"
|
||||
|
||||
static struct wdg_configuration {
|
||||
uint16_t used_flags;
|
||||
uint16_t bootup_flags;
|
||||
} wdg_configuration;
|
||||
|
||||
/**
|
||||
* @brief Initialize the watchdog timer for a specified timeout
|
||||
*
|
||||
* It is important to note that this function returns the achieved timeout
|
||||
* for this hardware. For hardware independence this should be checked when
|
||||
* scheduling updates. Other hardware dependent details may need to be
|
||||
* considered such as a window time which sets a minimum update time,
|
||||
* and this function should return a recommended delay for clearing.
|
||||
*
|
||||
* For the STM32 nominal clock rate is 32 khz, but for the maximum clock rate of
|
||||
* 60 khz and a prescaler of 4 yields a clock rate of 15 khz. The delay that is
|
||||
* set in the watchdog assumes the nominal clock rate, but the delay for FreeRTOS
|
||||
* to use is 75% of the minimal delay.
|
||||
*
|
||||
* @returns Maximum recommended delay between updates based on PIOS_WATCHDOG_TIMEOUT constant
|
||||
*/
|
||||
uint16_t PIOS_WDG_Init()
|
||||
{
|
||||
uint16_t delay = ((uint32_t)PIOS_WATCHDOG_TIMEOUT * 60) / 16;
|
||||
|
||||
if (delay > 0x0fff) {
|
||||
delay = 0x0fff;
|
||||
}
|
||||
#if defined(PIOS_INCLUDE_WDG)
|
||||
DBGMCU_APB1PeriphConfig(DBGMCU_IWDG_STOP, ENABLE); // OP-1272 : write in APB1 register
|
||||
IWDG_WriteAccessCmd(IWDG_WriteAccess_Enable);
|
||||
IWDG_SetPrescaler(IWDG_Prescaler_16);
|
||||
IWDG_SetReload(delay);
|
||||
IWDG_ReloadCounter();
|
||||
IWDG_Enable();
|
||||
|
||||
// watchdog flags now stored in backup registers
|
||||
PWR_BackupAccessCmd(ENABLE);
|
||||
|
||||
wdg_configuration.bootup_flags = RTC_ReadBackupRegister(PIOS_WDG_REGISTER);
|
||||
#endif
|
||||
return delay;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Register a module against the watchdog
|
||||
*
|
||||
* There are two ways to use PIOS WDG: this is for when
|
||||
* multiple modules must be monitored. In this case they
|
||||
* must first register against the watchdog system and
|
||||
* only when all of the modules have been updated with the
|
||||
* watchdog be cleared. Each module must have its own
|
||||
* bit in the 16 bit
|
||||
*
|
||||
* @param[in] flag the bit this module wants to use
|
||||
* @returns True if that bit is unregistered
|
||||
*/
|
||||
bool PIOS_WDG_RegisterFlag(uint16_t flag_requested)
|
||||
{
|
||||
// flag are being registered so we are in module initialization phase
|
||||
// clear the WDG to prevent timeout while initializing modules. (OP-815)
|
||||
PIOS_WDG_Clear();
|
||||
|
||||
/* Fail if flag already registered */
|
||||
if (wdg_configuration.used_flags & flag_requested) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// FIXME: Protect with semaphore
|
||||
wdg_configuration.used_flags |= flag_requested;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Function called by modules to indicate they are still running
|
||||
*
|
||||
* This function will set this flag in the active flags register (which is
|
||||
* a backup regsiter) and if all the registered flags are set will clear
|
||||
* the watchdog and set only this flag in the backup register
|
||||
*
|
||||
* @param[in] flag the flag to set
|
||||
* @return true if the watchdog cleared, false if flags are pending
|
||||
*/
|
||||
bool PIOS_WDG_UpdateFlag(uint16_t flag)
|
||||
{
|
||||
// we can probably avoid using a semaphore here which will be good for
|
||||
// efficiency and not blocking critical tasks. race condition could
|
||||
// overwrite their flag update, but unlikely to block _all_ of them
|
||||
// for the timeout window
|
||||
uint16_t cur_flags = RTC_ReadBackupRegister(PIOS_WDG_REGISTER);
|
||||
|
||||
if ((cur_flags | flag) == wdg_configuration.used_flags) {
|
||||
PIOS_WDG_Clear();
|
||||
RTC_WriteBackupRegister(PIOS_WDG_REGISTER, flag);
|
||||
return true;
|
||||
} else {
|
||||
RTC_WriteBackupRegister(PIOS_WDG_REGISTER, cur_flags | flag);
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Returns the flags that were set at bootup
|
||||
*
|
||||
* This is used for diagnostics, if only one flag not set this
|
||||
* was likely the module that wasn't running before reset
|
||||
*
|
||||
* @return The active flags register from bootup
|
||||
*/
|
||||
uint16_t PIOS_WDG_GetBootupFlags()
|
||||
{
|
||||
return wdg_configuration.bootup_flags;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Returns the currently active flags
|
||||
*
|
||||
* For external monitoring
|
||||
*
|
||||
* @return The active flags register
|
||||
*/
|
||||
uint16_t PIOS_WDG_GetActiveFlags()
|
||||
{
|
||||
return RTC_ReadBackupRegister(PIOS_WDG_REGISTER);
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Clear the watchdog timer
|
||||
*
|
||||
* This function must be called at the appropriate delay to prevent a reset event occuring
|
||||
*/
|
||||
void PIOS_WDG_Clear(void)
|
||||
{
|
||||
#if defined(PIOS_INCLUDE_WDG)
|
||||
IWDG_ReloadCounter();
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_WDG */
|
189
flight/pios/stm32f30x/startup.c
Normal file
189
flight/pios/stm32f30x/startup.c
Normal file
@ -0,0 +1,189 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
*
|
||||
* @file startup.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2013
|
||||
* @brief C based startup of F3
|
||||
* @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 <string.h>
|
||||
#include <stm32f30x.h>
|
||||
|
||||
/* prototype for main() that tells us not to worry about it possibly returning */
|
||||
extern int main(void) __attribute__((noreturn));
|
||||
|
||||
/* prototype our _main() to avoid prolog/epilog insertion and other related junk */
|
||||
void _main(void) __attribute__((noreturn, naked, no_instrument_function));
|
||||
|
||||
/** default handler for CPU exceptions */
|
||||
static void default_cpu_handler(void) __attribute__((noreturn, naked, no_instrument_function));
|
||||
|
||||
/** BSS symbols XXX should have a header that defines all of these */
|
||||
extern char _sbss, _ebss;
|
||||
|
||||
/** DATA symbols XXX should have a header that defines all of these */
|
||||
extern char _sidata, _sdata, _edata, _sfast, _efast;
|
||||
|
||||
/** The bootstrap/IRQ stack XXX should define size somewhere else */
|
||||
char irq_stack[1024] __attribute__((section(".irqstack")));
|
||||
|
||||
/** exception handler */
|
||||
typedef void (vector)(void);
|
||||
|
||||
/** CortexM3 CPU vectors */
|
||||
struct cm3_vectors {
|
||||
void *initial_stack;
|
||||
vector *entry;
|
||||
vector *vectors[14];
|
||||
};
|
||||
|
||||
/**
|
||||
* Initial startup code.
|
||||
*/
|
||||
void _main(void)
|
||||
{
|
||||
// load the stack base for the current stack before we attempt to branch to any function
|
||||
// that might bounds-check the stack
|
||||
asm volatile ("mov r10, %0" : : "r" (&irq_stack[0]) :);
|
||||
|
||||
/* enable usage, bus and memory faults */
|
||||
SCB->SHCSR |= SCB_SHCSR_USGFAULTENA_Msk | SCB_SHCSR_BUSFAULTENA_Msk | SCB_SHCSR_MEMFAULTENA_Msk;
|
||||
|
||||
/* configure FP state save behaviour - automatic, lazy save */
|
||||
FPU->FPCCR |= FPU_FPCCR_ASPEN_Msk | FPU_FPCCR_LSPEN_Msk;
|
||||
|
||||
/* configure default FPU state */
|
||||
FPU->FPDSCR |= FPU_FPDSCR_DN_Msk; /* enable Default NaN */
|
||||
FPU->FPDSCR |= FPU_FPDSCR_FZ_Msk; /* Use flush to zero for very
|
||||
* small values. */
|
||||
|
||||
/* enable the FPU */
|
||||
SCB->CPACR |= (0xf << 20); // turn on CP10/11 for FP support on cores that implement it
|
||||
|
||||
/* copy initialised data from flash to RAM */
|
||||
memcpy(&_sdata, &_sidata, &_edata - &_sdata);
|
||||
|
||||
/* zero the BSS */
|
||||
memset(&_sbss, 0, &_ebss - &_sbss);
|
||||
|
||||
/* zero any 'fast' RAM that's been used */
|
||||
memset(&_sfast, 0, &_efast - &_sfast);
|
||||
|
||||
/* fill most of the IRQ/bootstrap stack with a watermark pattern so we can measure how much is used */
|
||||
/* leave a little space at the top in case memset() isn't a leaf with no locals */
|
||||
memset(&irq_stack, 0xa5, sizeof(irq_stack) - 64);
|
||||
|
||||
/* call main */
|
||||
(void)main();
|
||||
}
|
||||
|
||||
/**
|
||||
* Default handler for CPU exceptions.
|
||||
*/
|
||||
static void default_cpu_handler(void)
|
||||
{
|
||||
for (;;) {
|
||||
;
|
||||
}
|
||||
}
|
||||
|
||||
static void default_NMI_Handler()
|
||||
{
|
||||
default_cpu_handler();
|
||||
}
|
||||
static void default_HardFault_Handler()
|
||||
{
|
||||
default_cpu_handler();
|
||||
}
|
||||
static void default_MemManage_Handler()
|
||||
{
|
||||
default_cpu_handler();
|
||||
}
|
||||
static void default_BusFault_Handler()
|
||||
{
|
||||
default_cpu_handler();
|
||||
}
|
||||
static void default_UsageFault_Handler()
|
||||
{
|
||||
default_cpu_handler();
|
||||
}
|
||||
static void default_DebugMon_Handler()
|
||||
{
|
||||
default_cpu_handler();
|
||||
}
|
||||
static void default_vPortSVCHandler()
|
||||
{
|
||||
default_cpu_handler();
|
||||
}
|
||||
static void default_xPortPendSVHandler()
|
||||
{
|
||||
default_cpu_handler();
|
||||
}
|
||||
static void default_xPortSysTickHandler()
|
||||
{
|
||||
default_cpu_handler();
|
||||
}
|
||||
|
||||
|
||||
/** Prototype for optional exception vector handlers */
|
||||
#define HANDLER(_name) extern vector _name __attribute__((weak, alias("default_" #_name)))
|
||||
|
||||
/* standard CMSIS vector names */
|
||||
HANDLER(NMI_Handler);
|
||||
HANDLER(HardFault_Handler);
|
||||
HANDLER(MemManage_Handler);
|
||||
HANDLER(BusFault_Handler);
|
||||
HANDLER(UsageFault_Handler);
|
||||
HANDLER(DebugMon_Handler);
|
||||
/* these vectors point directly to the relevant FreeRTOS functions if they are defined */
|
||||
HANDLER(vPortSVCHandler);
|
||||
HANDLER(xPortPendSVHandler);
|
||||
HANDLER(xPortSysTickHandler);
|
||||
|
||||
/** CortexM3 vector table */
|
||||
struct cm3_vectors cpu_vectors __attribute((section(".cpu_vectors"))) =
|
||||
{
|
||||
.initial_stack = &irq_stack[sizeof(irq_stack)],
|
||||
.entry = (vector *)_main,
|
||||
.vectors = {
|
||||
NMI_Handler,
|
||||
HardFault_Handler,
|
||||
MemManage_Handler,
|
||||
BusFault_Handler,
|
||||
UsageFault_Handler,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
vPortSVCHandler,
|
||||
DebugMon_Handler, // Maybe
|
||||
0,
|
||||
xPortPendSVHandler,
|
||||
xPortSysTickHandler,
|
||||
}
|
||||
};
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
309
flight/pios/stm32f30x/vectors_stm32f30x.c
Normal file
309
flight/pios/stm32f30x/vectors_stm32f30x.c
Normal file
@ -0,0 +1,309 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
*
|
||||
* @file vector_stm32f4xx.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2013
|
||||
* @brief C based vectors for F4
|
||||
* @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
|
||||
*/
|
||||
|
||||
/** interrupt handler */
|
||||
typedef void (vector)(void);
|
||||
|
||||
/** default interrupt handler */
|
||||
static void default_io_handler(void)
|
||||
{
|
||||
for (;;) {
|
||||
;
|
||||
}
|
||||
}
|
||||
|
||||
/** prototypes an interrupt handler */
|
||||
#define HANDLER(_name) extern vector _name __attribute__((weak, alias("default_io_handler")))
|
||||
|
||||
HANDLER(Reserved_IRQHandler); // Reserved
|
||||
HANDLER(WWDG_IRQHandler); // Window WatchDog
|
||||
HANDLER(PVD_IRQHandler); // PVD through EXTI Line detection
|
||||
HANDLER(TAMP_STAMP_IRQHandler); // Tamper and TimeStamps through the EXTI line
|
||||
HANDLER(RTC_WKUP_IRQHandler); // RTC Wakeup through the EXTI line
|
||||
HANDLER(FLASH_IRQHandler); // FLASH
|
||||
HANDLER(RCC_IRQHandler); // RCC
|
||||
HANDLER(EXTI0_IRQHandler); // EXTI Line0
|
||||
HANDLER(EXTI1_IRQHandler); // EXTI Line1
|
||||
HANDLER(EXTI2_TS_IRQHandler); // EXTI Line2 and Touch Sense Interrupt
|
||||
HANDLER(EXTI3_IRQHandler); // EXTI Line3
|
||||
HANDLER(EXTI4_IRQHandler); // EXTI Line4
|
||||
HANDLER(DMA1_Channel1_IRQHandler); // DMA1 Channel 1
|
||||
HANDLER(DMA1_Channel2_IRQHandler); // DMA1 Channel 2
|
||||
HANDLER(DMA1_Channel3_IRQHandler); // DMA1 Channel 3
|
||||
HANDLER(DMA1_Channel4_IRQHandler); // DMA1 Channel 4
|
||||
HANDLER(DMA1_Channel5_IRQHandler); // DMA1 Channel 5
|
||||
HANDLER(DMA1_Channel6_IRQHandler); // DMA1 Channel 6
|
||||
HANDLER(DMA1_Channel7_IRQHandler); // DMA1 Channel 7
|
||||
HANDLER(ADC1_2_IRQHandler); // ADC1 and ADC2
|
||||
HANDLER(USB_HP_CAN1_TX_IRQHandler); // USB Device High Priority or CAN1 TX
|
||||
HANDLER(USB_LP_CAN1_RX0_IRQHandler); // USB Device Low Priority or CAN1 RX0
|
||||
HANDLER(CAN1_RX1_IRQHandler); // CAN1 RX1
|
||||
HANDLER(CAN1_SCE_IRQHandler); // CAN1 SCE
|
||||
HANDLER(EXTI9_5_IRQHandler); // External Line[9:5]s
|
||||
HANDLER(TIM1_BRK_TIM15_IRQHandler); // TIM1 Break and TIM15
|
||||
HANDLER(TIM1_UP_TIM16_IRQHandler); // TIM1 Update and TIM16
|
||||
HANDLER(TIM1_TRG_COM_TIM17_IRQHandler); // TIM1 Trigger and Commutation and TIM17
|
||||
HANDLER(TIM1_CC_IRQHandler); // TIM1 Capture Compare
|
||||
HANDLER(TIM2_IRQHandler); // TIM2
|
||||
HANDLER(TIM3_IRQHandler); // TIM3
|
||||
HANDLER(TIM4_IRQHandler); // TIM4
|
||||
HANDLER(I2C1_EV_EXTI23_IRQHandler); // I2C1 Event and EXTI23
|
||||
HANDLER(I2C1_ER_IRQHandler); // I2C1 Error
|
||||
HANDLER(I2C2_EV_EXTI24_IRQHandler); // I2C2 Event and EXTI24
|
||||
HANDLER(I2C2_ER_IRQHandler); // I2C2 Error
|
||||
HANDLER(SPI1_IRQHandler); // SPI1
|
||||
HANDLER(SPI2_IRQHandler); // SPI2
|
||||
HANDLER(USART1_EXTI25_IRQHandler); // USART1 and EXTI25
|
||||
HANDLER(USART2_EXTI26_IRQHandler); // USART2 and EXTI26
|
||||
HANDLER(USART3_EXTI28_IRQHandler); // USART3 and EXTI28
|
||||
HANDLER(EXTI15_10_IRQHandler); // External Line[15:10]s
|
||||
HANDLER(RTC_Alarm_IRQHandler); // RTC Alarm (A and B) through EXTI Line
|
||||
HANDLER(USB_WKUP_IRQHandler); // USB FS Wakeup through EXTI line
|
||||
HANDLER(TIM8_BRK_IRQHandler); // TIM8 Break
|
||||
HANDLER(TIM8_UP_IRQHandler); // TIM8 Update
|
||||
HANDLER(TIM8_TRG_COM_IRQHandler); // TIM8 Trigger and Commutation
|
||||
HANDLER(TIM8_CC_IRQHandler); // TIM8 Capture Compare
|
||||
HANDLER(ADC3_IRQHandler); // ADC3
|
||||
HANDLER(SPI3_IRQHandler); // SPI3
|
||||
HANDLER(UART4_EXTI34_IRQHandler); // UART4 and EXTI34
|
||||
HANDLER(UART5_EXTI35_IRQHandler); // UART5 and EXTI35
|
||||
HANDLER(TIM6_DAC_IRQHandler); // TIM6 and DAC1&2 underrun errors
|
||||
HANDLER(TIM7_IRQHandler); // TIM7
|
||||
HANDLER(DMA2_Channel1_IRQHandler); // DMA2 Channel 1
|
||||
HANDLER(DMA2_Channel2_IRQHandler); // DMA2 Channel 2
|
||||
HANDLER(DMA2_Channel3_IRQHandler); // DMA2 Channel 3
|
||||
HANDLER(DMA2_Channel4_IRQHandler); // DMA2 Channel 4
|
||||
HANDLER(DMA2_Channel5_IRQHandler); // DMA2 Channel 5
|
||||
HANDLER(ADC4_IRQHandler); // ADC4
|
||||
HANDLER(COMP1_2_3_IRQHandler); // COMP1, COMP2 and COMP3
|
||||
HANDLER(COMP4_5_6_IRQHandler); // COMP4, COMP5 and COMP6
|
||||
HANDLER(COMP7_IRQHandler); // COMP7
|
||||
HANDLER(USB_HP_IRQHandler); // USB High Priority remap
|
||||
HANDLER(USB_LP_IRQHandler); // USB Low Priority remap
|
||||
HANDLER(USB_WKUP_RMP_IRQHandler); // USB Wakup remap
|
||||
HANDLER(FPU_IRQHandler); // FPU
|
||||
|
||||
/* STM32F303xE */
|
||||
HANDLER(TAMPER_STAMP_IRQHandler);
|
||||
HANDLER(I2C1_EV_IRQHandler);
|
||||
HANDLER(USART1_IRQHandler);
|
||||
HANDLER(USART2_IRQHandler);
|
||||
HANDLER(USART3_IRQHandler);
|
||||
HANDLER(USBWakeUp_IRQHandler);
|
||||
HANDLER(FMC_IRQHandler);
|
||||
HANDLER(UART4_IRQHandler);
|
||||
HANDLER(UART5_IRQHandler);
|
||||
HANDLER(I2C3_EV_IRQHandler);
|
||||
HANDLER(I2C3_ER_IRQHandler);
|
||||
HANDLER(USBWakeUp_RMP_IRQHandler);
|
||||
HANDLER(TIM20_BRK_IRQHandler);
|
||||
HANDLER(TIM20_UP_IRQHandler);
|
||||
HANDLER(TIM20_TRG_COM_IRQHandler);
|
||||
HANDLER(TIM20_CC_IRQHandler);
|
||||
HANDLER(SPI4_IRQHandler);
|
||||
HANDLER(I2C2_EV_IRQHandler);
|
||||
|
||||
|
||||
/** stm32f30x interrupt vector table */
|
||||
vector *io_vectors[] __attribute__((section(".io_vectors"))) = {
|
||||
#ifdef STM32F303xC
|
||||
WWDG_IRQHandler, // Window WatchDog
|
||||
PVD_IRQHandler, // PVD through EXTI Line detection
|
||||
TAMP_STAMP_IRQHandler, // Tamper and TimeStamps through the EXTI line
|
||||
RTC_WKUP_IRQHandler, // RTC Wakeup through the EXTI line
|
||||
FLASH_IRQHandler, // FLASH
|
||||
RCC_IRQHandler, // RCC
|
||||
EXTI0_IRQHandler, // EXTI Line0
|
||||
EXTI1_IRQHandler, // EXTI Line1
|
||||
EXTI2_TS_IRQHandler, // EXTI Line2 and Touch Sense Interrupt
|
||||
EXTI3_IRQHandler, // EXTI Line3
|
||||
EXTI4_IRQHandler, // EXTI Line4
|
||||
DMA1_Channel1_IRQHandler, // DMA1 Channel 1
|
||||
DMA1_Channel2_IRQHandler, // DMA1 Channel 2
|
||||
DMA1_Channel3_IRQHandler, // DMA1 Channel 3
|
||||
DMA1_Channel4_IRQHandler, // DMA1 Channel 4
|
||||
DMA1_Channel5_IRQHandler, // DMA1 Channel 5
|
||||
DMA1_Channel6_IRQHandler, // DMA1 Channel 6
|
||||
DMA1_Channel7_IRQHandler, // DMA1 Channel 7
|
||||
ADC1_2_IRQHandler, // ADC1 and ADC2
|
||||
USB_HP_CAN1_TX_IRQHandler, // USB Device High Priority or CAN1 TX
|
||||
USB_LP_CAN1_RX0_IRQHandler, // USB Device Low Priority or CAN1 RX0
|
||||
CAN1_RX1_IRQHandler, // CAN1 RX1
|
||||
CAN1_SCE_IRQHandler, // CAN1 SCE
|
||||
EXTI9_5_IRQHandler, // External Line[9:5]s
|
||||
TIM1_BRK_TIM15_IRQHandler, // TIM1 Break and TIM15
|
||||
TIM1_UP_TIM16_IRQHandler, // TIM1 Update and TIM16
|
||||
TIM1_TRG_COM_TIM17_IRQHandler, // TIM1 Trigger and Commutation and TIM17
|
||||
TIM1_CC_IRQHandler, // TIM1 Capture Compare
|
||||
TIM2_IRQHandler, // TIM2
|
||||
TIM3_IRQHandler, // TIM3
|
||||
TIM4_IRQHandler, // TIM4
|
||||
I2C1_EV_EXTI23_IRQHandler, // I2C1 Event and EXTI23
|
||||
I2C1_ER_IRQHandler, // I2C1 Error
|
||||
I2C2_EV_EXTI24_IRQHandler, // I2C2 Event and EXTI24
|
||||
I2C2_ER_IRQHandler, // I2C2 Error
|
||||
SPI1_IRQHandler, // SPI1
|
||||
SPI2_IRQHandler, // SPI2
|
||||
USART1_EXTI25_IRQHandler, // USART1 and EXTI25
|
||||
USART2_EXTI26_IRQHandler, // USART2 and EXTI26
|
||||
USART3_EXTI28_IRQHandler, // USART3 and EXTI28
|
||||
EXTI15_10_IRQHandler, // External Line[15:10]s
|
||||
RTC_Alarm_IRQHandler, // RTC Alarm (A and B) through EXTI Line
|
||||
USB_WKUP_IRQHandler, // USB FS Wakeup through EXTI line
|
||||
TIM8_BRK_IRQHandler, // TIM8 Break
|
||||
TIM8_UP_IRQHandler, // TIM8 Update
|
||||
TIM8_TRG_COM_IRQHandler, // TIM8 Trigger and Commutation
|
||||
TIM8_CC_IRQHandler, // TIM8 Capture Compare
|
||||
ADC3_IRQHandler, // ADC3
|
||||
Reserved_IRQHandler, // reserved
|
||||
Reserved_IRQHandler, // reserved
|
||||
Reserved_IRQHandler, // reserved
|
||||
SPI3_IRQHandler, // SPI3
|
||||
UART4_EXTI34_IRQHandler, // UART4 and EXTI34
|
||||
UART5_EXTI35_IRQHandler, // UART5 and EXTI35
|
||||
TIM6_DAC_IRQHandler, // TIM6 and DAC1&2 underrun errors
|
||||
TIM7_IRQHandler, // TIM7
|
||||
DMA2_Channel1_IRQHandler, // DMA2 Channel 1
|
||||
DMA2_Channel2_IRQHandler, // DMA2 Channel 2
|
||||
DMA2_Channel3_IRQHandler, // DMA2 Channel 3
|
||||
DMA2_Channel4_IRQHandler, // DMA2 Channel 4
|
||||
DMA2_Channel5_IRQHandler, // DMA2 Channel 5
|
||||
ADC4_IRQHandler, // ADC4
|
||||
Reserved_IRQHandler, // reserved
|
||||
Reserved_IRQHandler, // reserved
|
||||
COMP1_2_3_IRQHandler, // COMP1, COMP2 and COMP3
|
||||
COMP4_5_6_IRQHandler, // COMP4, COMP5 and COMP6
|
||||
COMP7_IRQHandler, // COMP7
|
||||
Reserved_IRQHandler, // reserved
|
||||
Reserved_IRQHandler, // reserved
|
||||
Reserved_IRQHandler, // reserved
|
||||
Reserved_IRQHandler, // reserved
|
||||
Reserved_IRQHandler, // reserved
|
||||
Reserved_IRQHandler, // reserved
|
||||
Reserved_IRQHandler, // reserved
|
||||
USB_HP_IRQHandler, // USB High Priority remap
|
||||
USB_LP_IRQHandler, // USB Low Priority remap
|
||||
USB_WKUP_RMP_IRQHandler, // USB Wakup remap
|
||||
Reserved_IRQHandler, // reserved
|
||||
Reserved_IRQHandler, // reserved
|
||||
Reserved_IRQHandler, // reserved
|
||||
Reserved_IRQHandler, // reserved
|
||||
FPU_IRQHandler, // FPU
|
||||
#endif /* ifdef STM32F303xC */
|
||||
#ifdef STM32F303xE
|
||||
WWDG_IRQHandler, /*!< Window WatchDog Interrupt */
|
||||
PVD_IRQHandler, /*!< PVD through EXTI Line detection Interrupt */
|
||||
TAMPER_STAMP_IRQHandler, /*!< Tamper and TimeStamp interrupts */
|
||||
RTC_WKUP_IRQHandler, /*!< RTC Wakeup interrupt through the EXTI lines 17, 19 & 20 */
|
||||
FLASH_IRQHandler, /*!< FLASH global Interrupt */
|
||||
RCC_IRQHandler, /*!< RCC global Interrupt */
|
||||
EXTI0_IRQHandler, /*!< EXTI Line0 Interrupt */
|
||||
EXTI1_IRQHandler, /*!< EXTI Line1 Interrupt */
|
||||
EXTI2_TS_IRQHandler, /*!< EXTI Line2 Interrupt and Touch Sense Interrupt */
|
||||
EXTI3_IRQHandler, /*!< EXTI Line3 Interrupt */
|
||||
EXTI4_IRQHandler, /*!< EXTI Line4 Interrupt */
|
||||
DMA1_Channel1_IRQHandler, /*!< DMA1 Channel 1 Interrupt */
|
||||
DMA1_Channel2_IRQHandler, /*!< DMA1 Channel 2 Interrupt */
|
||||
DMA1_Channel3_IRQHandler, /*!< DMA1 Channel 3 Interrupt */
|
||||
DMA1_Channel4_IRQHandler, /*!< DMA1 Channel 4 Interrupt */
|
||||
DMA1_Channel5_IRQHandler, /*!< DMA1 Channel 5 Interrupt */
|
||||
DMA1_Channel6_IRQHandler, /*!< DMA1 Channel 6 Interrupt */
|
||||
DMA1_Channel7_IRQHandler, /*!< DMA1 Channel 7 Interrupt */
|
||||
ADC1_2_IRQHandler, /*!< ADC1 & ADC2 Interrupts */
|
||||
USB_HP_CAN1_TX_IRQHandler, /*!< USB Device High Priority or CAN1 TX Interrupts */
|
||||
USB_LP_CAN1_RX0_IRQHandler, /*!< USB Device Low Priority or CAN1 RX0 Interrupts */
|
||||
CAN1_RX1_IRQHandler, /*!< CAN1 RX1 Interrupt */
|
||||
CAN1_SCE_IRQHandler, /*!< CAN1 SCE Interrupt */
|
||||
EXTI9_5_IRQHandler, /*!< External Line[9:5] Interrupts */
|
||||
TIM1_BRK_TIM15_IRQHandler, /*!< TIM1 Break and TIM15 Interrupts */
|
||||
TIM1_UP_TIM16_IRQHandler, /*!< TIM1 Update and TIM16 Interrupts */
|
||||
TIM1_TRG_COM_TIM17_IRQHandler, /*!< TIM1 Trigger and Commutation and TIM17 Interrupt */
|
||||
TIM1_CC_IRQHandler, /*!< TIM1 Capture Compare Interrupt */
|
||||
TIM2_IRQHandler, /*!< TIM2 global Interrupt */
|
||||
TIM3_IRQHandler, /*!< TIM3 global Interrupt */
|
||||
TIM4_IRQHandler, /*!< TIM4 global Interrupt */
|
||||
I2C1_EV_IRQHandler, /*!< I2C1 Event Interrupt */
|
||||
I2C1_ER_IRQHandler, /*!< I2C1 Error Interrupt */
|
||||
I2C2_EV_IRQHandler, /*!< I2C2 Event Interrupt */
|
||||
I2C2_ER_IRQHandler, /*!< I2C2 Error Interrupt */
|
||||
SPI1_IRQHandler, /*!< SPI1 global Interrupt */
|
||||
SPI2_IRQHandler, /*!< SPI2 global Interrupt */
|
||||
USART1_IRQHandler, /*!< USART1 global Interrupt */
|
||||
USART2_IRQHandler, /*!< USART2 global Interrupt */
|
||||
USART3_IRQHandler, /*!< USART3 global Interrupt */
|
||||
EXTI15_10_IRQHandler, /*!< External Line[15:10] Interrupts */
|
||||
RTC_Alarm_IRQHandler, /*!< RTC Alarm (A and B) through EXTI Line Interrupt */
|
||||
USBWakeUp_IRQHandler, /*!< USB Wakeup Interrupt */
|
||||
TIM8_BRK_IRQHandler, /*!< TIM8 Break Interrupt */
|
||||
TIM8_UP_IRQHandler, /*!< TIM8 Update Interrupt */
|
||||
TIM8_TRG_COM_IRQHandler, /*!< TIM8 Trigger and Commutation Interrupt */
|
||||
TIM8_CC_IRQHandler, /*!< TIM8 Capture Compare Interrupt */
|
||||
ADC3_IRQHandler, /*!< ADC3 global Interrupt */
|
||||
FMC_IRQHandler, /*!< FMC global Interrupt */
|
||||
Reserved_IRQHandler,
|
||||
Reserved_IRQHandler,
|
||||
SPI3_IRQHandler, /*!< SPI3 global Interrupt */
|
||||
UART4_IRQHandler, /*!< UART4 global Interrupt */
|
||||
UART5_IRQHandler, /*!< UART5 global Interrupt */
|
||||
TIM6_DAC_IRQHandler, /*!< TIM6 global and DAC1&2 underrun error interrupts */
|
||||
TIM7_IRQHandler, /*!< TIM7 global Interrupt */
|
||||
DMA2_Channel1_IRQHandler, /*!< DMA2 Channel 1 global Interrupt */
|
||||
DMA2_Channel2_IRQHandler, /*!< DMA2 Channel 2 global Interrupt */
|
||||
DMA2_Channel3_IRQHandler, /*!< DMA2 Channel 3 global Interrupt */
|
||||
DMA2_Channel4_IRQHandler, /*!< DMA2 Channel 4 global Interrupt */
|
||||
DMA2_Channel5_IRQHandler, /*!< DMA2 Channel 5 global Interrupt */
|
||||
ADC4_IRQHandler, /*!< ADC4 global Interrupt */
|
||||
Reserved_IRQHandler,
|
||||
Reserved_IRQHandler,
|
||||
COMP1_2_3_IRQHandler, /*!< COMP1, COMP2 and COMP3 global Interrupt */
|
||||
COMP4_5_6_IRQHandler, /*!< COMP5, COMP6 and COMP4 global Interrupt */
|
||||
COMP7_IRQHandler, /*!< COMP7 global Interrupt */
|
||||
Reserved_IRQHandler,
|
||||
Reserved_IRQHandler,
|
||||
Reserved_IRQHandler,
|
||||
Reserved_IRQHandler,
|
||||
Reserved_IRQHandler,
|
||||
I2C3_EV_IRQHandler, /*!< I2C3 event interrupt */
|
||||
I2C3_ER_IRQHandler, /*!< I2C3 error interrupt */
|
||||
USB_HP_IRQHandler, /*!< USB High Priority global Interrupt remap */
|
||||
USB_LP_IRQHandler, /*!< USB Low Priority global Interrupt remap */
|
||||
USBWakeUp_RMP_IRQHandler, /*!< USB Wakeup Interrupt remap */
|
||||
TIM20_BRK_IRQHandler, /*!< TIM20 Break Interrupt */
|
||||
TIM20_UP_IRQHandler, /*!< TIM20 Update Interrupt */
|
||||
TIM20_TRG_COM_IRQHandler, /*!< TIM20 Trigger and Commutation Interrupt */
|
||||
TIM20_CC_IRQHandler, /*!< TIM20 Capture Compare Interrupt */
|
||||
FPU_IRQHandler, /*!< Floating point Interrupt */
|
||||
Reserved_IRQHandler,
|
||||
Reserved_IRQHandler,
|
||||
SPI4_IRQHandler /*!< SPI4 global Interrupt */
|
||||
#endif /* ifdef STM32F303xE */
|
||||
};
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
@ -15,7 +15,7 @@ LINKER_SCRIPTS_COMPAT = $(PIOS_DEVLIB)link_$(BOARD)_fw_memory.ld \
|
||||
$(PIOS_DEVLIB)link_$(BOARD)_sections_compat.ld
|
||||
|
||||
# Compiler options implied by the F4xx
|
||||
CDEFS += -DSTM32F4XX
|
||||
CDEFS += -DSTM32F4XX -DSTM32F4
|
||||
ifeq ($(CHIPFAMILY),STM32F427_437xx)
|
||||
CDEFS += -DPIOS_TARGET_PROVIDES_FAST_HEAP
|
||||
#large heap support must be enabled if SRAM > 128K
|
||||
|
@ -159,7 +159,7 @@ static bool i2c_adapter_wait_for_stopped(struct pios_i2c_adapter *i2c_adapter);
|
||||
static void i2c_adapter_reset_bus(struct pios_i2c_adapter *i2c_adapter);
|
||||
|
||||
static void i2c_adapter_log_fault(enum pios_i2c_error_type type);
|
||||
static bool i2c_adapter_callback_handler(struct pios_i2c_adapter *i2c_adapter);
|
||||
static bool i2c_adapter_callback_handler(struct pios_i2c_adapter *i2c_adapter, signed portBASE_TYPE *pxHigherPriorityTaskWoken);
|
||||
|
||||
static const struct i2c_adapter_transition i2c_adapter_transitions[I2C_STATE_NUM_STATES] = {
|
||||
[I2C_STATE_FSM_FAULT] = {
|
||||
@ -420,18 +420,19 @@ static void go_stopping(struct pios_i2c_adapter *i2c_adapter)
|
||||
|
||||
I2C_ITConfig(i2c_adapter->cfg->regs, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR, DISABLE);
|
||||
|
||||
#ifdef USE_FREERTOS
|
||||
if (xSemaphoreGiveFromISR(i2c_adapter->sem_ready, &pxHigherPriorityTaskWoken) != pdTRUE) {
|
||||
#if defined(I2C_HALT_ON_ERRORS)
|
||||
PIOS_DEBUG_Assert(0);
|
||||
#endif
|
||||
}
|
||||
portEND_SWITCHING_ISR(pxHigherPriorityTaskWoken); /* FIXME: is this the right place for this? */
|
||||
#endif /* USE_FREERTOS */
|
||||
|
||||
if (i2c_adapter->callback) {
|
||||
i2c_adapter_callback_handler(i2c_adapter);
|
||||
i2c_adapter_callback_handler(i2c_adapter, &pxHigherPriorityTaskWoken);
|
||||
} else {
|
||||
#ifdef USE_FREERTOS
|
||||
if (xSemaphoreGiveFromISR(i2c_adapter->sem_ready, &pxHigherPriorityTaskWoken) != pdTRUE) {
|
||||
#if defined(I2C_HALT_ON_ERRORS)
|
||||
PIOS_DEBUG_Assert(0);
|
||||
#endif
|
||||
}
|
||||
#endif /* USE_FREERTOS */
|
||||
}
|
||||
|
||||
portEND_SWITCHING_ISR(pxHigherPriorityTaskWoken); /* FIXME: is this the right place for this? */
|
||||
}
|
||||
|
||||
|
||||
@ -853,18 +854,8 @@ static bool i2c_adapter_fsm_terminated(struct pios_i2c_adapter *i2c_adapter)
|
||||
|
||||
|
||||
uint32_t i2c_cb_count = 0;
|
||||
static bool i2c_adapter_callback_handler(struct pios_i2c_adapter *i2c_adapter)
|
||||
static bool i2c_adapter_callback_handler(struct pios_i2c_adapter *i2c_adapter, signed portBASE_TYPE *pxHigherPriorityTaskWoken)
|
||||
{
|
||||
bool semaphore_success = true;
|
||||
|
||||
/* Wait for the transfer to complete */
|
||||
#ifdef USE_FREERTOS
|
||||
portTickType timeout;
|
||||
timeout = i2c_adapter->cfg->transfer_timeout_ms / portTICK_RATE_MS;
|
||||
semaphore_success &= (xSemaphoreTake(i2c_adapter->sem_ready, timeout) == pdTRUE);
|
||||
xSemaphoreGive(i2c_adapter->sem_ready);
|
||||
#endif /* USE_FREERTOS */
|
||||
|
||||
/* transfer_timeout_ticks is set by PIOS_I2C_Transfer_Callback */
|
||||
/* Spin waiting for the transfer to finish */
|
||||
while (!i2c_adapter_fsm_terminated(i2c_adapter)) {
|
||||
@ -885,17 +876,10 @@ static bool i2c_adapter_callback_handler(struct pios_i2c_adapter *i2c_adapter)
|
||||
i2c_adapter_fsm_init(i2c_adapter);
|
||||
}
|
||||
|
||||
// Execute user supplied function
|
||||
i2c_adapter->callback();
|
||||
|
||||
i2c_cb_count++;
|
||||
|
||||
#ifdef USE_FREERTOS
|
||||
/* Unlock the bus */
|
||||
xSemaphoreGive(i2c_adapter->sem_busy);
|
||||
if (!semaphore_success) {
|
||||
i2c_timeout_counter++;
|
||||
}
|
||||
xSemaphoreGiveFromISR(i2c_adapter->sem_busy, pxHigherPriorityTaskWoken);
|
||||
|
||||
#else
|
||||
PIOS_IRQ_Disable();
|
||||
i2c_adapter->busy = 0;
|
||||
@ -903,7 +887,14 @@ static bool i2c_adapter_callback_handler(struct pios_i2c_adapter *i2c_adapter)
|
||||
#endif /* USE_FREERTOS */
|
||||
|
||||
|
||||
return (!i2c_adapter->bus_error) && semaphore_success;
|
||||
// Execute user supplied function
|
||||
if (i2c_adapter->callback()) {
|
||||
*pxHigherPriorityTaskWoken = pdTRUE;
|
||||
}
|
||||
|
||||
i2c_cb_count++;
|
||||
|
||||
return !i2c_adapter->bus_error;
|
||||
}
|
||||
|
||||
|
||||
@ -1149,7 +1140,31 @@ int32_t PIOS_I2C_Transfer(uint32_t i2c_id, const struct pios_i2c_txn txn_list[],
|
||||
0;
|
||||
}
|
||||
|
||||
int32_t PIOS_I2C_Transfer_Callback(uint32_t i2c_id, const struct pios_i2c_txn txn_list[], uint32_t num_txns, void *callback)
|
||||
static int32_t PIOS_I2C_Transfer_Callback_Internal(struct pios_i2c_adapter *i2c_adapter, const struct pios_i2c_txn txn_list[], uint32_t num_txns, pios_i2c_callback callback)
|
||||
{
|
||||
PIOS_DEBUG_Assert(i2c_adapter->curr_state == I2C_STATE_STOPPED);
|
||||
|
||||
i2c_adapter->first_txn = &txn_list[0];
|
||||
i2c_adapter->last_txn = &txn_list[num_txns - 1];
|
||||
i2c_adapter->active_txn = i2c_adapter->first_txn;
|
||||
i2c_adapter->bus_error = false;
|
||||
i2c_adapter->nack = false;
|
||||
i2c_adapter->callback = callback;
|
||||
|
||||
// Estimate bytes of transmission. Per txns: 1 adress byte + length
|
||||
i2c_adapter->transfer_timeout_ticks = num_txns;
|
||||
for (uint32_t i = 0; i < num_txns; i++) {
|
||||
i2c_adapter->transfer_timeout_ticks += txn_list[i].len;
|
||||
}
|
||||
// timeout if it takes eight times the expected time
|
||||
i2c_adapter->transfer_timeout_ticks <<= 3;
|
||||
|
||||
i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_START);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int32_t PIOS_I2C_Transfer_Callback(uint32_t i2c_id, const struct pios_i2c_txn txn_list[], uint32_t num_txns, pios_i2c_callback callback)
|
||||
{
|
||||
struct pios_i2c_adapter *i2c_adapter = (struct pios_i2c_adapter *)i2c_id;
|
||||
|
||||
@ -1162,8 +1177,6 @@ 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);
|
||||
|
||||
bool semaphore_success = true;
|
||||
|
||||
#ifdef USE_FREERTOS
|
||||
/* Lock the bus */
|
||||
portTickType timeout;
|
||||
@ -1172,37 +1185,54 @@ int32_t PIOS_I2C_Transfer_Callback(uint32_t i2c_id, const struct pios_i2c_txn tx
|
||||
return -2;
|
||||
}
|
||||
#else
|
||||
PIOS_IRQ_Disable();
|
||||
if (i2c_adapter->busy) {
|
||||
PIOS_IRQ_Enable();
|
||||
return -2;
|
||||
}
|
||||
i2c_adapter->busy = 1;
|
||||
PIOS_IRQ_Enable();
|
||||
#endif /* USE_FREERTOS */
|
||||
|
||||
PIOS_DEBUG_Assert(i2c_adapter->curr_state == I2C_STATE_STOPPED);
|
||||
return PIOS_I2C_Transfer_Callback_Internal(i2c_adapter, txn_list, num_txns, callback);
|
||||
}
|
||||
|
||||
i2c_adapter->first_txn = &txn_list[0];
|
||||
i2c_adapter->last_txn = &txn_list[num_txns - 1];
|
||||
i2c_adapter->active_txn = i2c_adapter->first_txn;
|
||||
int32_t PIOS_I2C_Transfer_CallbackFromISR(uint32_t i2c_id, const struct pios_i2c_txn txn_list[], uint32_t num_txns, pios_i2c_callback callback, bool *woken)
|
||||
{
|
||||
// FIXME: only supports transfer sizes up to 255 bytes
|
||||
struct pios_i2c_adapter *i2c_adapter = (struct pios_i2c_adapter *)i2c_id;
|
||||
|
||||
bool valid = PIOS_I2C_validate(i2c_adapter);
|
||||
|
||||
PIOS_Assert(valid)
|
||||
|
||||
PIOS_DEBUG_Assert(txn_list);
|
||||
PIOS_DEBUG_Assert(num_txns);
|
||||
|
||||
#ifdef USE_FREERTOS
|
||||
/* Make sure the done/ready semaphore is consumed before we start */
|
||||
semaphore_success &= (xSemaphoreTake(i2c_adapter->sem_ready, timeout) == pdTRUE);
|
||||
#endif
|
||||
signed portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE;
|
||||
|
||||
// used in the i2c_adapter_callback_handler function
|
||||
// Estimate bytes of transmission. Per txns: 1 adress byte + length
|
||||
i2c_adapter->transfer_timeout_ticks = num_txns;
|
||||
for (uint32_t i = 0; i < num_txns; i++) {
|
||||
i2c_adapter->transfer_timeout_ticks += txn_list[i].len;
|
||||
/* Lock the bus */
|
||||
bool locked = xSemaphoreTakeFromISR(i2c_adapter->sem_busy, &xHigherPriorityTaskWoken) == pdTRUE;
|
||||
|
||||
if (xHigherPriorityTaskWoken == pdTRUE) {
|
||||
*woken = true;
|
||||
}
|
||||
// timeout if it takes eight times the expected time
|
||||
i2c_adapter->transfer_timeout_ticks <<= 3;
|
||||
|
||||
i2c_adapter->callback = callback;
|
||||
i2c_adapter->bus_error = false;
|
||||
i2c_adapter_inject_event(i2c_adapter, I2C_EVENT_START);
|
||||
if (!locked) {
|
||||
return -2;
|
||||
}
|
||||
#else
|
||||
PIOS_IRQ_Disable();
|
||||
if (i2c_adapter->busy) {
|
||||
PIOS_IRQ_Enable();
|
||||
return -2;
|
||||
}
|
||||
i2c_adapter->busy = 1;
|
||||
PIOS_IRQ_Enable();
|
||||
#endif /* USE_FREERTOS */
|
||||
|
||||
return !semaphore_success ? -2 : 0;
|
||||
return PIOS_I2C_Transfer_Callback_Internal(i2c_adapter, txn_list, num_txns, callback);
|
||||
}
|
||||
|
||||
void PIOS_I2C_EV_IRQ_Handler(uint32_t i2c_id)
|
||||
|
24
flight/targets/boards/ccf3d/board-info.mk
Normal file
24
flight/targets/boards/ccf3d/board-info.mk
Normal file
@ -0,0 +1,24 @@
|
||||
BOARD_TYPE := 0x04
|
||||
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
|
||||
|
||||
# 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
|
||||
FW_BANK_BASE := 0x0800C000 # Start of firmware flash
|
||||
FW_BANK_SIZE := 0x00034000 # Should include FW_DESC_SIZE (208kB)
|
||||
|
||||
FW_DESC_SIZE := 0x00000064
|
||||
|
||||
OSCILLATOR_FREQ := 8000000
|
861
flight/targets/boards/ccf3d/board_hw_defs.c
Normal file
861
flight/targets/boards/ccf3d/board_hw_defs.c
Normal file
@ -0,0 +1,861 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @file board_hw_defs.c
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
|
||||
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* PhoenixPilot, http://github.com/PhoenixPilot, Copyright (C) 2012
|
||||
*
|
||||
* @addtogroup OpenPilotSystem OpenPilot System
|
||||
* @{
|
||||
* @addtogroup OpenPilotCore OpenPilot Core
|
||||
* @{
|
||||
* @brief Defines board specific static initializers for hardware for the CopterControl board.
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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
|
||||
*/
|
||||
|
||||
#if defined(PIOS_INCLUDE_LED)
|
||||
|
||||
#include <pios_led_priv.h>
|
||||
|
||||
static const struct pios_gpio pios_leds_cc3d[] = {
|
||||
[PIOS_LED_HEARTBEAT] = {
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_3,
|
||||
.GPIO_Mode = GPIO_Mode_OUT,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL,
|
||||
},
|
||||
},
|
||||
// .remap = GPIO_Remap_SWJ_JTAGDisable,
|
||||
.active_low = true
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_gpio_cfg pios_led_cfg_cc3d = {
|
||||
.gpios = pios_leds_cc3d,
|
||||
.num_gpios = NELEMENTS(pios_leds_cc3d),
|
||||
};
|
||||
|
||||
const struct pios_gpio_cfg *PIOS_BOARD_HW_DEFS_GetLedCfg(__attribute__((unused)) uint32_t board_revision)
|
||||
{
|
||||
return &pios_led_cfg_cc3d;
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_LED */
|
||||
|
||||
#if defined(PIOS_INCLUDE_SPI)
|
||||
|
||||
#include <pios_spi_priv.h>
|
||||
|
||||
/* Gyro interface */
|
||||
void PIOS_SPI_gyro_irq_handler(void);
|
||||
void DMA1_Channel2_IRQHandler() __attribute__((alias("PIOS_SPI_gyro_irq_handler")));
|
||||
void DMA1_Channel3_IRQHandler() __attribute__((alias("PIOS_SPI_gyro_irq_handler")));
|
||||
static const struct pios_spi_cfg pios_spi_gyro_cfg = {
|
||||
.regs = SPI1,
|
||||
.init = {
|
||||
.SPI_Mode = SPI_Mode_Master,
|
||||
.SPI_Direction = SPI_Direction_2Lines_FullDuplex,
|
||||
.SPI_DataSize = SPI_DataSize_8b,
|
||||
.SPI_NSS = SPI_NSS_Soft,
|
||||
.SPI_FirstBit = SPI_FirstBit_MSB,
|
||||
.SPI_CRCPolynomial = 7,
|
||||
.SPI_CPOL = SPI_CPOL_High,
|
||||
.SPI_CPHA = SPI_CPHA_2Edge,
|
||||
.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_16, /* 10 Mhz */
|
||||
},
|
||||
.use_crc = false,
|
||||
.dma = {
|
||||
.ahb_clk = RCC_AHBPeriph_DMA1,
|
||||
|
||||
.irq = {
|
||||
.flags = (DMA1_FLAG_TC2 | DMA1_FLAG_TE2 | DMA1_FLAG_HT2 | DMA1_FLAG_GL2),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Channel2_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
|
||||
.rx = {
|
||||
.channel = DMA1_Channel2,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR),
|
||||
.DMA_DIR = DMA_DIR_PeripheralSRC,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_Medium,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.channel = DMA1_Channel3,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR),
|
||||
.DMA_DIR = DMA_DIR_PeripheralDST,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_Medium,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
},
|
||||
.remap = GPIO_AF_5,
|
||||
.sclk = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_5,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL,
|
||||
},
|
||||
},
|
||||
.miso = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_6,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL,
|
||||
},
|
||||
},
|
||||
.mosi = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_7,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL,
|
||||
},
|
||||
},
|
||||
.slave_count = 1,
|
||||
.ssel = {
|
||||
{
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_4,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_OUT,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP
|
||||
},
|
||||
}
|
||||
},
|
||||
};
|
||||
|
||||
uint32_t pios_spi_gyro_id;
|
||||
void PIOS_SPI_gyro_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_SPI_IRQ_Handler(pios_spi_gyro_id);
|
||||
}
|
||||
|
||||
|
||||
/* Flash/Accel Interface
|
||||
*
|
||||
* NOTE: Leave this declared as const data so that it ends up in the
|
||||
* .rodata section (ie. Flash) rather than in the .bss section (RAM).
|
||||
*/
|
||||
void PIOS_SPI_flash_accel_irq_handler(void);
|
||||
void DMA1_Channel4_IRQHandler() __attribute__((alias("PIOS_SPI_flash_accel_irq_handler")));
|
||||
void DMA1_Channel5_IRQHandler() __attribute__((alias("PIOS_SPI_flash_accel_irq_handler")));
|
||||
static const struct pios_spi_cfg pios_spi_flash_accel_cfg_cc3d = {
|
||||
.regs = SPI2,
|
||||
.init = {
|
||||
.SPI_Mode = SPI_Mode_Master,
|
||||
.SPI_Direction = SPI_Direction_2Lines_FullDuplex,
|
||||
.SPI_DataSize = SPI_DataSize_8b,
|
||||
.SPI_NSS = SPI_NSS_Soft,
|
||||
.SPI_FirstBit = SPI_FirstBit_MSB,
|
||||
.SPI_CRCPolynomial = 7,
|
||||
.SPI_CPOL = SPI_CPOL_High,
|
||||
.SPI_CPHA = SPI_CPHA_2Edge,
|
||||
.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8,
|
||||
},
|
||||
.use_crc = false,
|
||||
.dma = {
|
||||
.ahb_clk = RCC_AHBPeriph_DMA1,
|
||||
|
||||
.irq = {
|
||||
.flags = (DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 | DMA1_FLAG_GL4),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Channel4_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
|
||||
.rx = {
|
||||
.channel = DMA1_Channel4,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI2->DR),
|
||||
.DMA_DIR = DMA_DIR_PeripheralSRC,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_High,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.channel = DMA1_Channel5,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI2->DR),
|
||||
.DMA_DIR = DMA_DIR_PeripheralDST,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_High,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
},
|
||||
.remap = GPIO_AF_5,
|
||||
.sclk = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_13,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL,
|
||||
},
|
||||
},
|
||||
.miso = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_14,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF, /* NOTE: was GPIO_Mode_IN_FLOATING */
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL,
|
||||
},
|
||||
},
|
||||
.mosi = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_15,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL,
|
||||
},
|
||||
},
|
||||
.slave_count = 2,
|
||||
.ssel = {
|
||||
{
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_12,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_OUT,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP,
|
||||
}
|
||||
},{
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_15,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_OUT,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP,
|
||||
},
|
||||
}
|
||||
},
|
||||
};
|
||||
|
||||
static uint32_t pios_spi_flash_accel_id;
|
||||
void PIOS_SPI_flash_accel_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_SPI_IRQ_Handler(pios_spi_flash_accel_id);
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_SPI */
|
||||
|
||||
#if defined(PIOS_INCLUDE_FLASH)
|
||||
#include "pios_flashfs_logfs_priv.h"
|
||||
#include "pios_flash_jedec_priv.h"
|
||||
|
||||
static const struct flashfs_logfs_cfg flashfs_m25p_cfg = {
|
||||
.fs_magic = 0x99abceef,
|
||||
.total_fs_size = 0x00200000, /* 2M bytes (32 sectors = entire chip) */
|
||||
.arena_size = 0x00010000, /* 256 * slot size */
|
||||
.slot_size = 0x00000100, /* 256 bytes */
|
||||
|
||||
.start_offset = 0, /* start at the beginning of the chip */
|
||||
.sector_size = 0x00010000, /* 64K bytes */
|
||||
.page_size = 0x00000100, /* 256 bytes */
|
||||
};
|
||||
|
||||
#include "pios_flash.h"
|
||||
|
||||
#endif /* PIOS_INCLUDE_FLASH */
|
||||
|
||||
/*
|
||||
* ADC system
|
||||
*/
|
||||
#if defined(PIOS_INCLUDE_ADC)
|
||||
#include "pios_adc_priv.h"
|
||||
extern void PIOS_ADC_handler(void);
|
||||
void DMA1_Channel1_IRQHandler() __attribute__((alias("PIOS_ADC_handler")));
|
||||
// Remap the ADC DMA handler to this one
|
||||
static const struct pios_adc_cfg pios_adc_cfg = {
|
||||
.dma = {
|
||||
.ahb_clk = RCC_AHBPeriph_DMA1,
|
||||
.irq = {
|
||||
.flags = (DMA1_FLAG_TC1 | DMA1_FLAG_TE1 | DMA1_FLAG_HT1 | DMA1_FLAG_GL1),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Channel1_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.channel = DMA1_Channel1,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&ADC1->DR,
|
||||
.DMA_DIR = DMA_DIR_PeripheralSRC,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Word,
|
||||
.DMA_Mode = DMA_Mode_Circular,
|
||||
.DMA_Priority = DMA_Priority_High,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
}
|
||||
},
|
||||
.half_flag = DMA1_IT_HT1,
|
||||
.full_flag = DMA1_IT_TC1,
|
||||
};
|
||||
|
||||
void PIOS_ADC_handler()
|
||||
{
|
||||
PIOS_ADC_DMA_Handler();
|
||||
}
|
||||
#endif /* if defined(PIOS_INCLUDE_ADC) */
|
||||
|
||||
#include "pios_tim_priv.h"
|
||||
|
||||
static const TIM_TimeBaseInitTypeDef tim_1_2_3_4_time_base = {
|
||||
.TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1,
|
||||
.TIM_ClockDivision = TIM_CKD_DIV1,
|
||||
.TIM_CounterMode = TIM_CounterMode_Up,
|
||||
.TIM_Period = ((1000000 / PIOS_SERVO_UPDATE_HZ) - 1),
|
||||
.TIM_RepetitionCounter = 0x0000,
|
||||
};
|
||||
|
||||
static const struct pios_tim_clock_cfg tim_1_cfg = {
|
||||
.timer = TIM1,
|
||||
.time_base_init = &tim_1_2_3_4_time_base,
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = TIM1_CC_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_tim_clock_cfg tim_2_cfg = {
|
||||
.timer = TIM2,
|
||||
.time_base_init = &tim_1_2_3_4_time_base,
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = TIM2_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_tim_clock_cfg tim_3_cfg = {
|
||||
.timer = TIM3,
|
||||
.time_base_init = &tim_1_2_3_4_time_base,
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = TIM3_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_tim_clock_cfg tim_4_cfg = {
|
||||
.timer = TIM4,
|
||||
.time_base_init = &tim_1_2_3_4_time_base,
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = TIM4_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
#include <pios_servo_config.h>
|
||||
|
||||
#define GPIO_AF_PA1_TIM2 GPIO_AF_1
|
||||
#define GPIO_AF_PA0_TIM2 GPIO_AF_1
|
||||
#define GPIO_AF_PA8_TIM1 GPIO_AF_6
|
||||
#define GPIO_AF_PA2_TIM2 GPIO_AF_1
|
||||
#define GPIO_AF_PB6_TIM4 GPIO_AF_2
|
||||
#define GPIO_AF_PB5_TIM3 GPIO_AF_2
|
||||
#define GPIO_AF_PB0_TIM3 GPIO_AF_2
|
||||
#define GPIO_AF_PB1_TIM3 GPIO_AF_2
|
||||
#define GPIO_AF_PB9_TIM4 GPIO_AF_2
|
||||
#define GPIO_AF_PB8_TIM4 GPIO_AF_2
|
||||
#define GPIO_AF_PB7_TIM4 GPIO_AF_2
|
||||
#define GPIO_AF_PB4_TIM3 GPIO_AF_2
|
||||
#define GPIO_AF_PB11_TIM2 GPIO_AF_1
|
||||
|
||||
static const struct pios_tim_channel pios_tim_rcvrport_all_channels[] = {
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM4, 1, B, 6),
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM3, 2, B, 5),
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM3, 3, B, 0),
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM3, 4, B, 1),
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM2, 1, A, 0),
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM2, 2, A, 1),
|
||||
};
|
||||
|
||||
static const struct pios_tim_channel pios_tim_servoport_rcvrport_pins[] = {
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM4, 4, B, 9),
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM4, 3, B, 8),
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM4, 2, B, 7),
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM1, 1, A, 8),
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM3, 1, B, 4),
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM2, 3, A, 2),
|
||||
|
||||
// Receiver port pins
|
||||
// S3-S6 inputs are used as outputs in this case
|
||||
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM3, 3, B, 0),
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM3, 4, B, 1),
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM2, 1, A, 0),
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM2, 2, A, 1),
|
||||
};
|
||||
|
||||
static const struct pios_tim_channel pios_tim_ppm_flexi_port = TIM_SERVO_CHANNEL_CONFIG(TIM2, 4, B, 11);
|
||||
|
||||
|
||||
#if defined(PIOS_INCLUDE_USART)
|
||||
|
||||
#define GPIO_AF_USART1 GPIO_AF_7
|
||||
#define GPIO_AF_USART3 GPIO_AF_7
|
||||
|
||||
|
||||
#include "pios_usart_priv.h"
|
||||
#include "pios_usart_config.h"
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_main_cfg = USART_CONFIG(USART1, A, 10, A, 9);
|
||||
static const struct pios_usart_cfg pios_usart_flexi_cfg = USART_CONFIG(USART3, B, 11, B, 10);
|
||||
#endif /* PIOS_INCLUDE_USART */
|
||||
|
||||
#if defined(PIOS_INCLUDE_RTC)
|
||||
/*
|
||||
* Realtime Clock (RTC)
|
||||
*/
|
||||
#include <pios_rtc_priv.h>
|
||||
|
||||
void PIOS_RTC_IRQ_Handler(void);
|
||||
void RTC_WKUP_IRQHandler() __attribute__((alias("PIOS_RTC_IRQ_Handler")));
|
||||
static const struct pios_rtc_cfg pios_rtc_main_cfg = {
|
||||
.clksrc = RCC_RTCCLKSource_HSE_Div32,
|
||||
.prescaler = 25 - 1, // 8Mhz / 32 / 16 / 25 => 625Hz
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = RTC_WKUP_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
void PIOS_RTC_IRQ_Handler(void)
|
||||
{
|
||||
PIOS_RTC_irq_handler();
|
||||
}
|
||||
|
||||
#endif /* if defined(PIOS_INCLUDE_RTC) */
|
||||
|
||||
#if defined(PIOS_INCLUDE_SERVO) && defined(PIOS_INCLUDE_TIM)
|
||||
/*
|
||||
* Servo outputs
|
||||
*/
|
||||
#include <pios_servo_priv.h>
|
||||
|
||||
const struct pios_servo_cfg pios_servo_cfg = {
|
||||
.tim_oc_init = {
|
||||
.TIM_OCMode = TIM_OCMode_PWM1,
|
||||
.TIM_OutputState = TIM_OutputState_Enable,
|
||||
.TIM_OutputNState = TIM_OutputNState_Disable,
|
||||
.TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION,
|
||||
.TIM_OCPolarity = TIM_OCPolarity_High,
|
||||
.TIM_OCNPolarity = TIM_OCPolarity_High,
|
||||
.TIM_OCIdleState = TIM_OCIdleState_Reset,
|
||||
.TIM_OCNIdleState = TIM_OCNIdleState_Reset,
|
||||
},
|
||||
.channels = pios_tim_servoport_rcvrport_pins,
|
||||
.num_channels = 6,
|
||||
};
|
||||
|
||||
const struct pios_servo_cfg pios_servo_rcvr_cfg = {
|
||||
.tim_oc_init = {
|
||||
.TIM_OCMode = TIM_OCMode_PWM1,
|
||||
.TIM_OutputState = TIM_OutputState_Enable,
|
||||
.TIM_OutputNState = TIM_OutputNState_Disable,
|
||||
.TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION,
|
||||
.TIM_OCPolarity = TIM_OCPolarity_High,
|
||||
.TIM_OCNPolarity = TIM_OCPolarity_High,
|
||||
.TIM_OCIdleState = TIM_OCIdleState_Reset,
|
||||
.TIM_OCNIdleState = TIM_OCNIdleState_Reset,
|
||||
},
|
||||
.channels = pios_tim_servoport_rcvrport_pins,
|
||||
.num_channels = NELEMENTS(pios_tim_servoport_rcvrport_pins),
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_SERVO && PIOS_INCLUDE_TIM */
|
||||
|
||||
/*
|
||||
* PPM Inputs
|
||||
*/
|
||||
#if defined(PIOS_INCLUDE_PPM)
|
||||
#include <pios_ppm_priv.h>
|
||||
|
||||
const struct pios_ppm_cfg pios_ppm_cfg = {
|
||||
.tim_ic_init = {
|
||||
.TIM_ICPolarity = TIM_ICPolarity_Rising,
|
||||
.TIM_ICSelection = TIM_ICSelection_DirectTI,
|
||||
.TIM_ICPrescaler = TIM_ICPSC_DIV1,
|
||||
.TIM_ICFilter = 0x0,
|
||||
},
|
||||
/* Use only the first channel for ppm */
|
||||
.channels = &pios_tim_rcvrport_all_channels[0],
|
||||
.num_channels = 1,
|
||||
};
|
||||
|
||||
const struct pios_ppm_cfg pios_ppm_pin8_cfg = {
|
||||
.tim_ic_init = {
|
||||
.TIM_ICPolarity = TIM_ICPolarity_Rising,
|
||||
.TIM_ICSelection = TIM_ICSelection_DirectTI,
|
||||
.TIM_ICPrescaler = TIM_ICPSC_DIV1,
|
||||
.TIM_ICFilter = 0x0,
|
||||
},
|
||||
/* Use only the first channel for ppm */
|
||||
.channels = &pios_tim_rcvrport_all_channels[5],
|
||||
.num_channels = 1,
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_PPM */
|
||||
|
||||
#if defined(PIOS_INCLUDE_PPM_FLEXI)
|
||||
#include <pios_ppm_priv.h>
|
||||
|
||||
const struct pios_ppm_cfg pios_ppm_flexi_cfg = {
|
||||
.tim_ic_init = {
|
||||
.TIM_ICPolarity = TIM_ICPolarity_Rising,
|
||||
.TIM_ICSelection = TIM_ICSelection_DirectTI,
|
||||
.TIM_ICPrescaler = TIM_ICPSC_DIV1,
|
||||
.TIM_ICFilter = 0x0,
|
||||
},
|
||||
.channels = &pios_tim_ppm_flexi_port,
|
||||
.num_channels = 1,
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_PPM_FLEXI */
|
||||
|
||||
/*
|
||||
* PWM Inputs
|
||||
*/
|
||||
#if defined(PIOS_INCLUDE_PWM)
|
||||
#include <pios_pwm_priv.h>
|
||||
|
||||
const struct pios_pwm_cfg pios_pwm_cfg = {
|
||||
.tim_ic_init = {
|
||||
.TIM_ICPolarity = TIM_ICPolarity_Rising,
|
||||
.TIM_ICSelection = TIM_ICSelection_DirectTI,
|
||||
.TIM_ICPrescaler = TIM_ICPSC_DIV1,
|
||||
.TIM_ICFilter = 0x0,
|
||||
},
|
||||
.channels = pios_tim_rcvrport_all_channels,
|
||||
.num_channels = NELEMENTS(pios_tim_rcvrport_all_channels),
|
||||
};
|
||||
|
||||
const struct pios_pwm_cfg pios_pwm_with_ppm_cfg = {
|
||||
.tim_ic_init = {
|
||||
.TIM_ICPolarity = TIM_ICPolarity_Rising,
|
||||
.TIM_ICSelection = TIM_ICSelection_DirectTI,
|
||||
.TIM_ICPrescaler = TIM_ICPSC_DIV1,
|
||||
.TIM_ICFilter = 0x0,
|
||||
},
|
||||
/* Leave the first channel for PPM use and use the rest for PWM */
|
||||
.channels = &pios_tim_rcvrport_all_channels[1],
|
||||
.num_channels = NELEMENTS(pios_tim_rcvrport_all_channels) - 1,
|
||||
};
|
||||
|
||||
#endif /* if defined(PIOS_INCLUDE_PWM) */
|
||||
|
||||
|
||||
/*
|
||||
* SONAR Inputs
|
||||
*/
|
||||
#if defined(PIOS_INCLUDE_HCSR04)
|
||||
#include <pios_hcsr04_priv.h>
|
||||
|
||||
static const struct pios_tim_channel pios_tim_hcsr04_port_all_channels[] = {
|
||||
{
|
||||
.timer = TIM3,
|
||||
.timer_chan = TIM_Channel_2,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_5,
|
||||
.GPIO_Mode = GPIO_Mode_IPD,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
.remap = GPIO_PartialRemap_TIM3,
|
||||
},
|
||||
};
|
||||
|
||||
const struct pios_hcsr04_cfg pios_hcsr04_cfg = {
|
||||
.tim_ic_init = {
|
||||
.TIM_ICPolarity = TIM_ICPolarity_Rising,
|
||||
.TIM_ICSelection = TIM_ICSelection_DirectTI,
|
||||
.TIM_ICPrescaler = TIM_ICPSC_DIV1,
|
||||
.TIM_ICFilter = 0x0,
|
||||
},
|
||||
.channels = pios_tim_hcsr04_port_all_channels,
|
||||
.num_channels = NELEMENTS(pios_tim_hcsr04_port_all_channels),
|
||||
.trigger = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_6,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
};
|
||||
#endif /* if defined(PIOS_INCLUDE_HCSR04) */
|
||||
|
||||
#if defined(PIOS_INCLUDE_I2C)
|
||||
|
||||
#include <pios_i2c_priv.h>
|
||||
|
||||
/*
|
||||
* I2C Adapters
|
||||
*/
|
||||
|
||||
void PIOS_I2C_flexi_adapter_ev_irq_handler(void);
|
||||
void PIOS_I2C_flexi_adapter_er_irq_handler(void);
|
||||
void I2C2_EV_EXTI24_IRQHandler() __attribute__((alias("PIOS_I2C_flexi_adapter_ev_irq_handler")));
|
||||
void I2C2_ER_IRQHandler() __attribute__((alias("PIOS_I2C_flexi_adapter_er_irq_handler")));
|
||||
|
||||
static const struct pios_i2c_adapter_cfg pios_i2c_flexi_adapter_cfg = {
|
||||
.regs = I2C2,
|
||||
.init = {
|
||||
.I2C_Mode = I2C_Mode_I2C,
|
||||
.I2C_OwnAddress1 = 0,
|
||||
.I2C_Ack = I2C_Ack_Enable,
|
||||
.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit,
|
||||
.I2C_DigitalFilter = 0x00,
|
||||
.I2C_AnalogFilter = I2C_AnalogFilter_Enable,
|
||||
.I2C_Timing = 0x70310309, // 50kHz I2C @ 8MHz input -> PRESC=0x7, SCLDEL=0x3, SDADEL=0x1, SCLH=0x03, SCLL=0x09
|
||||
},
|
||||
.remapSDA = GPIO_AF_4, /* I2C1, I2C2 */
|
||||
.remapSCL = GPIO_AF_4, /* I2C1, I2C2 */
|
||||
.transfer_timeout_ms = 50,
|
||||
.scl = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_OType = GPIO_OType_OD,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP,
|
||||
},
|
||||
},
|
||||
.sda = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_OType = GPIO_OType_OD,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP,
|
||||
},
|
||||
},
|
||||
.event = {
|
||||
.flags = 0, /* FIXME: check this */
|
||||
.init = {
|
||||
.NVIC_IRQChannel = I2C2_EV_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.error = {
|
||||
.flags = 0, /* FIXME: check this */
|
||||
.init = {
|
||||
.NVIC_IRQChannel = I2C2_ER_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
uint32_t pios_i2c_flexi_adapter_id;
|
||||
void PIOS_I2C_flexi_adapter_ev_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_I2C_EV_IRQ_Handler(pios_i2c_flexi_adapter_id);
|
||||
}
|
||||
|
||||
void PIOS_I2C_flexi_adapter_er_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_I2C_ER_IRQ_Handler(pios_i2c_flexi_adapter_id);
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_I2C */
|
||||
|
||||
#if defined(PIOS_INCLUDE_RCVR)
|
||||
#include "pios_rcvr_priv.h"
|
||||
|
||||
#endif /* PIOS_INCLUDE_RCVR */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
#include "pios_usb_priv.h"
|
||||
|
||||
static const struct pios_usb_cfg pios_usb_main_cfg_cc3d = {
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.vsense = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_14,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN,
|
||||
.GPIO_OType = GPIO_OType_OD,
|
||||
.GPIO_PuPd = GPIO_PuPd_DOWN,
|
||||
},
|
||||
},
|
||||
.vsense_active_low = false
|
||||
};
|
||||
|
||||
const struct pios_usb_cfg *PIOS_BOARD_HW_DEFS_GetUsbCfg(__attribute__((unused)) uint32_t board_revision)
|
||||
{
|
||||
return &pios_usb_main_cfg_cc3d;
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
|
||||
/**
|
||||
* Configuration for MPU6000 chip
|
||||
*/
|
||||
#if defined(PIOS_INCLUDE_MPU6000)
|
||||
#include "pios_mpu6000.h"
|
||||
static const struct pios_exti_cfg pios_exti_mpu6000_cfg __exti_config = {
|
||||
.vector = PIOS_MPU6000_IRQHandler,
|
||||
.line = EXTI_Line3,
|
||||
.pin = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_3,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN,
|
||||
.GPIO_OType = GPIO_OType_OD,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL,
|
||||
},
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = EXTI3_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.exti = {
|
||||
.init = {
|
||||
.EXTI_Line = EXTI_Line3, // matches above GPIO pin
|
||||
.EXTI_Mode = EXTI_Mode_Interrupt,
|
||||
.EXTI_Trigger = EXTI_Trigger_Rising,
|
||||
.EXTI_LineCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_mpu6000_cfg pios_mpu6000_cfg = {
|
||||
.exti_cfg = &pios_exti_mpu6000_cfg,
|
||||
.Fifo_store = PIOS_MPU6000_FIFO_TEMP_OUT | PIOS_MPU6000_FIFO_GYRO_X_OUT | PIOS_MPU6000_FIFO_GYRO_Y_OUT | PIOS_MPU6000_FIFO_GYRO_Z_OUT,
|
||||
// Clock at 8 khz, downsampled by 8 for 1000 Hz
|
||||
.Smpl_rate_div_no_dlp = 7,
|
||||
// Clock at 1 khz, downsampled by 1 for 1000 Hz
|
||||
.Smpl_rate_div_dlp = 0,
|
||||
.interrupt_cfg = PIOS_MPU6000_INT_CLR_ANYRD,
|
||||
.interrupt_en = PIOS_MPU6000_INTEN_DATA_RDY,
|
||||
.User_ctl = PIOS_MPU6000_USERCTL_DIS_I2C,
|
||||
.Pwr_mgmt_clk = PIOS_MPU6000_PWRMGMT_PLL_X_CLK,
|
||||
.accel_range = PIOS_MPU6000_ACCEL_8G,
|
||||
.gyro_range = PIOS_MPU6000_SCALE_2000_DEG,
|
||||
.filter = PIOS_MPU6000_LOWPASS_256_HZ,
|
||||
.orientation = PIOS_MPU6000_TOP_180DEG,
|
||||
.fast_prescaler = PIOS_SPI_PRESCALER_4,
|
||||
.std_prescaler = PIOS_SPI_PRESCALER_64,
|
||||
.max_downsample = 2
|
||||
};
|
||||
|
||||
const struct pios_mpu6000_cfg *PIOS_BOARD_HW_DEFS_GetMPU6000Cfg(__attribute__((unused)) uint32_t board_revision)
|
||||
{
|
||||
return &pios_mpu6000_cfg;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_MPU6000 */
|
||||
|
29
flight/targets/boards/ccf3d/bootloader/Makefile
Normal file
29
flight/targets/boards/ccf3d/bootloader/Makefile
Normal file
@ -0,0 +1,29 @@
|
||||
#
|
||||
# Copyright (c) 2015, The LibrePilot Project, http://www.librepilot.org
|
||||
# Copyright (c) 2009-2013, The OpenPilot Team, http://www.openpilot.org
|
||||
#
|
||||
# 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 FLIGHT_MAKEFILE
|
||||
$(error Top level Makefile must be used to build this target)
|
||||
endif
|
||||
|
||||
include ../board-info.mk
|
||||
include $(FLIGHT_ROOT_DIR)/make/firmware-defs.mk
|
||||
include $(FLIGHT_ROOT_DIR)/make/boot-defs.mk
|
||||
include $(FLIGHT_ROOT_DIR)/make/common-defs.mk
|
||||
|
||||
$(info Making bootloader for CCF3D, board revision $(BOARD_REVISION))
|
115
flight/targets/boards/ccf3d/bootloader/inc/common.h
Normal file
115
flight/targets/boards/ccf3d/bootloader/inc/common.h
Normal file
@ -0,0 +1,115 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup CopterControlBL CopterControl BootLoader
|
||||
* @brief These files contain the code to the CopterControl Bootloader.
|
||||
*
|
||||
* @{
|
||||
* @file common.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief This file contains various common defines for the BootLoader
|
||||
* @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
|
||||
*/
|
||||
#ifndef COMMON_H_
|
||||
#define COMMON_H_
|
||||
|
||||
// #include "board.h"
|
||||
|
||||
typedef enum {
|
||||
start, keepgoing,
|
||||
} DownloadAction;
|
||||
|
||||
/**************************************************/
|
||||
/* OP_DFU states */
|
||||
/**************************************************/
|
||||
|
||||
typedef enum {
|
||||
DFUidle, // 0
|
||||
uploading, // 1
|
||||
wrong_packet_received, // 2
|
||||
too_many_packets, // 3
|
||||
too_few_packets, // 4
|
||||
Last_operation_Success, // 5
|
||||
downloading, // 6
|
||||
BLidle, // 7
|
||||
Last_operation_failed, // 8
|
||||
uploadingStarting, // 9
|
||||
outsideDevCapabilities, // 10
|
||||
CRC_Fail, // 11
|
||||
failed_jump,
|
||||
// 12
|
||||
} DFUStates;
|
||||
/**************************************************/
|
||||
/* OP_DFU commands */
|
||||
/**************************************************/
|
||||
typedef enum {
|
||||
Reserved, // 0
|
||||
Req_Capabilities, // 1
|
||||
Rep_Capabilities, // 2
|
||||
EnterDFU, // 3
|
||||
JumpFW, // 4
|
||||
Reset, // 5
|
||||
Abort_Operation, // 6
|
||||
Upload, // 7
|
||||
Op_END, // 8
|
||||
Download_Req, // 9
|
||||
Download, // 10
|
||||
Status_Request, // 11
|
||||
Status_Rep
|
||||
// 12
|
||||
} DFUCommands;
|
||||
|
||||
typedef enum {
|
||||
High_Density, Medium_Density
|
||||
} DeviceType;
|
||||
/**************************************************/
|
||||
/* OP_DFU transfer types */
|
||||
/**************************************************/
|
||||
typedef enum {
|
||||
FW, // 0
|
||||
Descript
|
||||
// 2
|
||||
} DFUTransfer;
|
||||
/**************************************************/
|
||||
/* OP_DFU transfer port */
|
||||
/**************************************************/
|
||||
typedef enum {
|
||||
Usb, // 0
|
||||
Serial
|
||||
// 2
|
||||
} DFUPort;
|
||||
/**************************************************/
|
||||
/* OP_DFU programable programable HW types */
|
||||
/**************************************************/
|
||||
typedef enum {
|
||||
Self_flash, // 0
|
||||
Remote_flash_via_spi
|
||||
// 1
|
||||
} DFUProgType;
|
||||
/**************************************************/
|
||||
/* OP_DFU programable sources */
|
||||
/**************************************************/
|
||||
#define USB 0
|
||||
#define SPI 1
|
||||
|
||||
#define DownloadDelay 100000
|
||||
|
||||
#define MAX_DEL_RETRYS 3
|
||||
#define MAX_WRI_RETRYS 3
|
||||
|
||||
#endif /* COMMON_H_ */
|
53
flight/targets/boards/ccf3d/bootloader/inc/pios_config.h
Normal file
53
flight/targets/boards/ccf3d/bootloader/inc/pios_config.h
Normal file
@ -0,0 +1,53 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup CopterControlBL CopterControl BootLoader
|
||||
* @brief These files contain the code to the CopterControl Bootloader.
|
||||
* @{
|
||||
* @file pios_config.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief PiOS configuration header.
|
||||
* Central compile time config for the project.
|
||||
* In particular, pios_config.h is where you define which PiOS libraries
|
||||
* and features are included in the firmware.
|
||||
* @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
|
||||
*/
|
||||
|
||||
#ifndef PIOS_CONFIG_H
|
||||
#define PIOS_CONFIG_H
|
||||
|
||||
/* Enable/Disable PiOS modules */
|
||||
#define PIOS_INCLUDE_DELAY
|
||||
#define PIOS_INCLUDE_SYS
|
||||
#define PIOS_INCLUDE_IRQ
|
||||
#define PIOS_INCLUDE_GPIO
|
||||
#define PIOS_INCLUDE_USB
|
||||
#define PIOS_INCLUDE_USB_HID
|
||||
#define PIOS_INCLUDE_LED
|
||||
#define PIOS_INCLUDE_IAP
|
||||
#define PIOS_INCLUDE_COM
|
||||
#define PIOS_INCLUDE_COM_MSG
|
||||
#define PIOS_INCLUDE_BL_HELPER
|
||||
#define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT
|
||||
|
||||
#endif /* PIOS_CONFIG_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -0,0 +1,53 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_USB_BOARD Board specific USB definitions
|
||||
* @brief Board specific USB definitions
|
||||
* @{
|
||||
*
|
||||
* @file pios_usb_board_data.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Board specific USB definitions
|
||||
* @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
|
||||
*/
|
||||
|
||||
#ifndef PIOS_USB_BOARD_DATA_H
|
||||
#define PIOS_USB_BOARD_DATA_H
|
||||
|
||||
// Note : changing below length will require changes to the USB buffer setup
|
||||
#define PIOS_USB_BOARD_HID_DATA_LENGTH 64
|
||||
|
||||
#define PIOS_USB_BOARD_EP_NUM 2
|
||||
|
||||
#include <pios_usb_defs.h> /* struct usb_* */
|
||||
|
||||
#define PIOS_USB_BOARD_PRODUCT_ID USB_PRODUCT_ID_COPTERCONTROL
|
||||
#define PIOS_USB_BOARD_DEVICE_VER USB_OP_DEVICE_VER(USB_OP_BOARD_ID_COPTERCONTROL, USB_OP_BOARD_MODE_BL)
|
||||
#define PIOS_USB_BOARD_SN_SUFFIX "+BL"
|
||||
|
||||
/*
|
||||
* The bootloader uses a simplified report structure
|
||||
* BL: <REPORT_ID><DATA>...<DATA>
|
||||
* FW: <REPORT_ID><LENGTH><DATA>...<DATA>
|
||||
* This define changes the behaviour in pios_usb_hid.c
|
||||
*/
|
||||
#define PIOS_USB_BOARD_BL_HID_HAS_NO_LENGTH_BYTE
|
||||
|
||||
#endif /* PIOS_USB_BOARD_DATA_H */
|
228
flight/targets/boards/ccf3d/bootloader/main.c
Normal file
228
flight/targets/boards/ccf3d/bootloader/main.c
Normal file
@ -0,0 +1,228 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup CopterControlBL CopterControl BootLoader
|
||||
* @brief These files contain the code to the CopterControl Bootloader.
|
||||
*
|
||||
* @{
|
||||
* @file main.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief This is the file with the main function of the OpenPilot BootLoader
|
||||
* @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>
|
||||
#include <pios_board_info.h>
|
||||
#include <op_dfu.h>
|
||||
#include <usb_lib.h>
|
||||
#include <pios_iap.h>
|
||||
#include <fifo_buffer.h>
|
||||
#include <pios_com_msg.h>
|
||||
#include <pios_board_init.h>
|
||||
|
||||
extern void FLASH_Download();
|
||||
#define BSL_HOLD_STATE ((PIOS_USB_DETECT_GPIO_PORT->IDR & PIOS_USB_DETECT_GPIO_PIN) ? 0 : 1)
|
||||
|
||||
/* Private typedef -----------------------------------------------------------*/
|
||||
typedef void (*pFunction)(void);
|
||||
/* Private define ------------------------------------------------------------*/
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
pFunction Jump_To_Application;
|
||||
uint32_t JumpAddress;
|
||||
|
||||
/// LEDs PWM
|
||||
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
|
||||
|
||||
|
||||
////////////////////////////////////////
|
||||
uint8_t tempcount = 0;
|
||||
|
||||
/* Extern variables ----------------------------------------------------------*/
|
||||
DFUStates DeviceState;
|
||||
int16_t status = 0;
|
||||
uint8_t JumpToApp = FALSE;
|
||||
uint8_t GO_dfu = FALSE;
|
||||
uint8_t USB_connected = FALSE;
|
||||
uint8_t User_DFU_request = FALSE;
|
||||
static uint8_t mReceive_Buffer[63];
|
||||
/* Private function prototypes -----------------------------------------------*/
|
||||
uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count);
|
||||
uint8_t processRX();
|
||||
void jump_to_app();
|
||||
|
||||
int main()
|
||||
{
|
||||
PIOS_SYS_Init();
|
||||
PIOS_Board_Init();
|
||||
PIOS_IAP_Init();
|
||||
|
||||
USB_connected = PIOS_USB_CableConnected(0);
|
||||
|
||||
if (PIOS_IAP_CheckRequest() == TRUE) {
|
||||
PIOS_DELAY_WaitmS(1000);
|
||||
User_DFU_request = TRUE;
|
||||
PIOS_IAP_ClearRequest();
|
||||
}
|
||||
|
||||
GO_dfu = (USB_connected == TRUE) || (User_DFU_request == TRUE);
|
||||
|
||||
if (GO_dfu == TRUE) {
|
||||
PIOS_Board_Init();
|
||||
if (User_DFU_request == TRUE) {
|
||||
DeviceState = DFUidle;
|
||||
} else {
|
||||
DeviceState = BLidle;
|
||||
}
|
||||
} else {
|
||||
JumpToApp = TRUE;
|
||||
}
|
||||
|
||||
uint32_t stopwatch = 0;
|
||||
uint32_t prev_ticks = PIOS_DELAY_GetuS();
|
||||
while (TRUE) {
|
||||
/* Update the stopwatch */
|
||||
uint32_t elapsed_ticks = PIOS_DELAY_GetuSSince(prev_ticks);
|
||||
prev_ticks += elapsed_ticks;
|
||||
stopwatch += elapsed_ticks;
|
||||
|
||||
if (JumpToApp == TRUE) {
|
||||
jump_to_app();
|
||||
}
|
||||
|
||||
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;
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT);
|
||||
period2 = 0;
|
||||
break;
|
||||
default: // error
|
||||
period1 = 5000;
|
||||
sweep_steps1 = 100;
|
||||
period2 = 5000;
|
||||
sweep_steps2 = 100;
|
||||
}
|
||||
|
||||
if (period1 != 0) {
|
||||
if (LedPWM(period1, sweep_steps1, stopwatch)) {
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT);
|
||||
} else {
|
||||
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
|
||||
}
|
||||
} else {
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT);
|
||||
}
|
||||
|
||||
if (period2 != 0) {
|
||||
if (LedPWM(period2, sweep_steps2, stopwatch)) {
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT);
|
||||
} else {
|
||||
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
|
||||
}
|
||||
} else {
|
||||
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
|
||||
}
|
||||
|
||||
if (stopwatch > 50 * 1000 * 1000) {
|
||||
stopwatch = 0;
|
||||
}
|
||||
if ((stopwatch > 6 * 1000 * 1000) && ((DeviceState == BLidle) || (DeviceState == DFUidle && !USB_connected))) {
|
||||
JumpToApp = TRUE;
|
||||
}
|
||||
|
||||
processRX();
|
||||
DataDownload(start);
|
||||
}
|
||||
}
|
||||
|
||||
void jump_to_app()
|
||||
{
|
||||
const struct pios_board_info *bdinfo = &pios_board_info_blob;
|
||||
|
||||
uint32_t fwIrqStackBase = (*(__IO uint32_t *)bdinfo->fw_base) & 0xFFFE0000;
|
||||
|
||||
// Check for the two possible irqstack locations (sram or core coupled sram)
|
||||
if (fwIrqStackBase == 0x20000000 || fwIrqStackBase == 0x10000000) {
|
||||
/* Jump to user application */
|
||||
FLASH_Lock();
|
||||
RCC_APB2PeriphResetCmd(0xffffffff, ENABLE);
|
||||
RCC_APB1PeriphResetCmd(0xffffffff, ENABLE);
|
||||
RCC_APB2PeriphResetCmd(0xffffffff, DISABLE);
|
||||
RCC_APB1PeriphResetCmd(0xffffffff, DISABLE);
|
||||
|
||||
_SetCNTR(0); // clear interrupt mask
|
||||
_SetISTR(0); // clear all requests
|
||||
|
||||
JumpAddress = *(__IO uint32_t *)(bdinfo->fw_base + 4);
|
||||
Jump_To_Application = (pFunction)JumpAddress;
|
||||
/* Initialize user application's Stack Pointer */
|
||||
__set_MSP(*(__IO uint32_t *)bdinfo->fw_base);
|
||||
Jump_To_Application();
|
||||
} else {
|
||||
DeviceState = failed_jump;
|
||||
return;
|
||||
}
|
||||
}
|
||||
uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count)
|
||||
{
|
||||
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 curr_sweep = (count / (pwm_period * pwm_sweep_steps)); /* ticks once per full sweep */
|
||||
|
||||
if (curr_sweep & 1) {
|
||||
pwm_duty = pwm_period - pwm_duty; /* reverse direction in odd sweeps */
|
||||
}
|
||||
return ((count % pwm_period) > pwm_duty) ? 1 : 0;
|
||||
}
|
||||
|
||||
uint8_t processRX()
|
||||
{
|
||||
if (PIOS_COM_MSG_Receive(PIOS_COM_TELEM_USB, mReceive_Buffer, sizeof(mReceive_Buffer))) {
|
||||
processComand(mReceive_Buffer);
|
||||
}
|
||||
return TRUE;
|
||||
}
|
||||
|
||||
int32_t platform_senddata(const uint8_t *msg, uint16_t msg_len)
|
||||
{
|
||||
return PIOS_COM_MSG_Send(PIOS_COM_TELEM_USB, msg, msg_len);
|
||||
}
|
102
flight/targets/boards/ccf3d/bootloader/pios_board.c
Normal file
102
flight/targets/boards/ccf3d/bootloader/pios_board.c
Normal file
@ -0,0 +1,102 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pios_board.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Defines board specific static initializers for hardware for the CopterControl board.
|
||||
* @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>
|
||||
#include <pios_board_info.h>
|
||||
|
||||
#include "pios_usb_board_data_priv.h"
|
||||
#include "pios_usb_desc_hid_cdc_priv.h"
|
||||
#include "pios_usb_desc_hid_only_priv.h"
|
||||
#include "pios_usbhook.h"
|
||||
|
||||
#include <pios_com_msg_priv.h>
|
||||
|
||||
/*
|
||||
* Pull in the board-specific static HW definitions.
|
||||
* Including .c files is a bit ugly but this allows all of
|
||||
* the HW definitions to be const and static to limit their
|
||||
* scope.
|
||||
*
|
||||
* NOTE: THIS IS THE ONLY PLACE THAT SHOULD EVER INCLUDE THIS FILE
|
||||
*/
|
||||
#include "../board_hw_defs.c"
|
||||
|
||||
uint32_t pios_com_telem_usb_id;
|
||||
|
||||
/**
|
||||
* PIOS_Board_Init()
|
||||
* initializes all the core subsystems on this specific hardware
|
||||
* called from System/openpilot.c
|
||||
*/
|
||||
static bool board_init_complete = false;
|
||||
void PIOS_Board_Init(void)
|
||||
{
|
||||
if (board_init_complete) {
|
||||
return;
|
||||
}
|
||||
|
||||
/* Enable Prefetch Buffer */
|
||||
FLASH_PrefetchBufferCmd(ENABLE);
|
||||
|
||||
/* Flash 2 wait state */
|
||||
FLASH_SetLatency(FLASH_Latency_2);
|
||||
|
||||
const struct pios_board_info *bdinfo = &pios_board_info_blob;
|
||||
|
||||
#if defined(PIOS_INCLUDE_LED)
|
||||
const struct pios_gpio_cfg *led_cfg = PIOS_BOARD_HW_DEFS_GetLedCfg(bdinfo->board_rev);
|
||||
PIOS_Assert(led_cfg);
|
||||
PIOS_LED_Init(led_cfg);
|
||||
#endif /* PIOS_INCLUDE_LED */
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
/* Initialize board specific USB data */
|
||||
PIOS_USB_BOARD_DATA_Init();
|
||||
|
||||
/* Activate the HID-only USB configuration */
|
||||
PIOS_USB_DESC_HID_ONLY_Init();
|
||||
|
||||
uint32_t pios_usb_id;
|
||||
PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg_cc3d);
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_HID) && defined(PIOS_INCLUDE_COM_MSG)
|
||||
uint32_t pios_usb_hid_id;
|
||||
if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_only_cfg, pios_usb_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
if (PIOS_COM_MSG_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_COM_MSG */
|
||||
|
||||
#endif /* PIOS_INCLUDE_USB */
|
||||
|
||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_CRC, ENABLE); // TODO Tirar
|
||||
|
||||
board_init_complete = true;
|
||||
}
|
||||
|
||||
void PIOS_ADC_DMA_Handler()
|
||||
{}
|
117
flight/targets/boards/ccf3d/firmware/Makefile
Normal file
117
flight/targets/boards/ccf3d/firmware/Makefile
Normal file
@ -0,0 +1,117 @@
|
||||
#
|
||||
# Copyright (C) 2015-2016, The LibrePilot Project, http://www.librepilot.org
|
||||
# Copyright (C) 2009-2013, The OpenPilot Team, http://www.openpilot.org
|
||||
# Copyright (C) 2012, PhoenixPilot, http://github.com/PhoenixPilot
|
||||
#
|
||||
# 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 FLIGHT_MAKEFILE
|
||||
$(error Top level Makefile must be used to build this target)
|
||||
endif
|
||||
|
||||
include ../board-info.mk
|
||||
include $(FLIGHT_ROOT_DIR)/make/firmware-defs.mk
|
||||
|
||||
# REVO C++ support
|
||||
USE_CXX = YES
|
||||
|
||||
# ARM DSP library
|
||||
USE_DSP_LIB ?= NO
|
||||
|
||||
DEBUG = NO
|
||||
|
||||
# List of mandatory modules to include
|
||||
MODULES += Sensors
|
||||
MODULES += StateEstimation
|
||||
MODULES += Stabilization
|
||||
MODULES += ManualControl
|
||||
MODULES += Receiver
|
||||
MODULES += Actuator
|
||||
MODULES += FirmwareIAP
|
||||
#MODULES += PathPlanner
|
||||
#MODULES += PathFollower
|
||||
#MODULES += Osd/osdoutout
|
||||
#MODULES += Logging
|
||||
MODULES += Telemetry
|
||||
#MODULES += Notify
|
||||
|
||||
OPTMODULES += Airspeed
|
||||
OPTMODULES += AutoTune
|
||||
OPTMODULES += GPS
|
||||
OPTMODULES += TxPID
|
||||
OPTMODULES += CameraStab
|
||||
OPTMODULES += CameraControl
|
||||
OPTMODULES += Battery
|
||||
OPTMODULES += ComUsbBridge
|
||||
OPTMODULES += UAVOMSPBridge
|
||||
OPTMODULES += UAVOMavlinkBridge
|
||||
|
||||
SRC += $(FLIGHTLIB)/notification.c
|
||||
|
||||
# Include all camera options
|
||||
CDEFS += -DUSE_INPUT_LPF -DUSE_GIMBAL_LPF -DUSE_GIMBAL_FF
|
||||
|
||||
# Some diagnostics
|
||||
CDEFS += -DDIAG_TASKS
|
||||
|
||||
# Misc options
|
||||
CFLAGS += -ffast-math
|
||||
|
||||
# List C source files here (C dependencies are automatically generated).
|
||||
# Use file-extension c for "c-only"-files
|
||||
ifndef TESTAPP
|
||||
## Application Core
|
||||
SRC += ../pios_usb_board_data.c
|
||||
SRC += $(OPMODULEDIR)/System/systemmod.c
|
||||
CPPSRC += $(OPSYSTEM)/coptercontrol.cpp
|
||||
SRC += $(OPSYSTEM)/pios_board.c
|
||||
SRC += $(FLIGHTLIB)/alarms.c
|
||||
SRC += $(OPUAVTALK)/uavtalk.c
|
||||
SRC += $(OPUAVOBJ)/uavobjectmanager.c
|
||||
SRC += $(OPUAVOBJ)/uavobjectpersistence.c
|
||||
SRC += $(OPUAVOBJ)/eventdispatcher.c
|
||||
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
|
||||
SRC += $(FLIGHTLIB)/plans.c
|
||||
SRC += $(FLIGHTLIB)/WorldMagModel.c
|
||||
SRC += $(FLIGHTLIB)/insgps13state.c
|
||||
SRC += $(FLIGHTLIB)/auxmagsupport.c
|
||||
SRC += $(FLIGHTLIB)/lednotification.c
|
||||
|
||||
## UAVObjects
|
||||
include ./UAVObjects.inc
|
||||
SRC += $(UAVOBJSRC)
|
||||
else
|
||||
## Test Code
|
||||
SRC += $(OPTESTS)/test_common.c
|
||||
SRC += $(OPTESTS)/$(TESTAPP).c
|
||||
endif
|
||||
|
||||
# Optional component libraries
|
||||
#include $(FLIGHTLIB)/rscode/library.mk
|
||||
#include $(FLIGHTLIB)/PyMite/pymite.mk
|
||||
|
||||
include $(FLIGHT_ROOT_DIR)/make/apps-defs.mk
|
||||
include $(FLIGHT_ROOT_DIR)/make/common-defs.mk
|
135
flight/targets/boards/ccf3d/firmware/UAVObjects.inc
Normal file
135
flight/targets/boards/ccf3d/firmware/UAVObjects.inc
Normal file
@ -0,0 +1,135 @@
|
||||
#
|
||||
# Copyright (C) 2016, The LibrePilot Project, http://www.librepilot.org
|
||||
# Copyright (C) 2009-2013, The OpenPilot Team, http://www.openpilot.org
|
||||
#
|
||||
# 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
|
||||
#
|
||||
|
||||
# These are the UAVObjects supposed to be build as part of the OpenPilot target
|
||||
# (all architectures)
|
||||
UAVOBJSRCFILENAMES =
|
||||
UAVOBJSRCFILENAMES += statusgrounddrive
|
||||
UAVOBJSRCFILENAMES += pidstatus
|
||||
UAVOBJSRCFILENAMES += statusvtolland
|
||||
UAVOBJSRCFILENAMES += statusvtolautotakeoff
|
||||
UAVOBJSRCFILENAMES += vtolselftuningstats
|
||||
UAVOBJSRCFILENAMES += accelgyrosettings
|
||||
UAVOBJSRCFILENAMES += accessorydesired
|
||||
UAVOBJSRCFILENAMES += actuatorcommand
|
||||
UAVOBJSRCFILENAMES += actuatordesired
|
||||
UAVOBJSRCFILENAMES += actuatorsettings
|
||||
UAVOBJSRCFILENAMES += attitudesettings
|
||||
UAVOBJSRCFILENAMES += attitudestate
|
||||
UAVOBJSRCFILENAMES += gyrostate
|
||||
UAVOBJSRCFILENAMES += gyrosensor
|
||||
UAVOBJSRCFILENAMES += accelstate
|
||||
UAVOBJSRCFILENAMES += accelsensor
|
||||
UAVOBJSRCFILENAMES += magsensor
|
||||
UAVOBJSRCFILENAMES += auxmagsensor
|
||||
UAVOBJSRCFILENAMES += auxmagsettings
|
||||
UAVOBJSRCFILENAMES += magstate
|
||||
UAVOBJSRCFILENAMES += barosensor
|
||||
UAVOBJSRCFILENAMES += airspeedsensor
|
||||
UAVOBJSRCFILENAMES += airspeedsettings
|
||||
UAVOBJSRCFILENAMES += airspeedstate
|
||||
UAVOBJSRCFILENAMES += debuglogsettings
|
||||
UAVOBJSRCFILENAMES += debuglogcontrol
|
||||
UAVOBJSRCFILENAMES += debuglogstatus
|
||||
UAVOBJSRCFILENAMES += debuglogentry
|
||||
UAVOBJSRCFILENAMES += flightbatterysettings
|
||||
UAVOBJSRCFILENAMES += firmwareiapobj
|
||||
UAVOBJSRCFILENAMES += flightbatterystate
|
||||
UAVOBJSRCFILENAMES += flightplancontrol
|
||||
UAVOBJSRCFILENAMES += flightplansettings
|
||||
UAVOBJSRCFILENAMES += flightplanstatus
|
||||
UAVOBJSRCFILENAMES += flighttelemetrystats
|
||||
UAVOBJSRCFILENAMES += gcstelemetrystats
|
||||
UAVOBJSRCFILENAMES += gcsreceiver
|
||||
UAVOBJSRCFILENAMES += gpspositionsensor
|
||||
UAVOBJSRCFILENAMES += gpssatellites
|
||||
UAVOBJSRCFILENAMES += gpstime
|
||||
UAVOBJSRCFILENAMES += gpsvelocitysensor
|
||||
UAVOBJSRCFILENAMES += gpssettings
|
||||
UAVOBJSRCFILENAMES += gpsextendedstatus
|
||||
UAVOBJSRCFILENAMES += fixedwingpathfollowersettings
|
||||
UAVOBJSRCFILENAMES += fixedwingpathfollowerstatus
|
||||
UAVOBJSRCFILENAMES += vtolpathfollowersettings
|
||||
UAVOBJSRCFILENAMES += groundpathfollowersettings
|
||||
UAVOBJSRCFILENAMES += homelocation
|
||||
UAVOBJSRCFILENAMES += i2cstats
|
||||
UAVOBJSRCFILENAMES += manualcontrolcommand
|
||||
UAVOBJSRCFILENAMES += manualcontrolsettings
|
||||
UAVOBJSRCFILENAMES += flightmodesettings
|
||||
UAVOBJSRCFILENAMES += mixersettings
|
||||
UAVOBJSRCFILENAMES += mixerstatus
|
||||
UAVOBJSRCFILENAMES += nedaccel
|
||||
UAVOBJSRCFILENAMES += objectpersistence
|
||||
UAVOBJSRCFILENAMES += oplinkreceiver
|
||||
UAVOBJSRCFILENAMES += overosyncstats
|
||||
UAVOBJSRCFILENAMES += overosyncsettings
|
||||
UAVOBJSRCFILENAMES += pathaction
|
||||
UAVOBJSRCFILENAMES += pathdesired
|
||||
UAVOBJSRCFILENAMES += pathplan
|
||||
UAVOBJSRCFILENAMES += pathstatus
|
||||
UAVOBJSRCFILENAMES += pathsummary
|
||||
UAVOBJSRCFILENAMES += positionstate
|
||||
UAVOBJSRCFILENAMES += ratedesired
|
||||
UAVOBJSRCFILENAMES += ekfconfiguration
|
||||
UAVOBJSRCFILENAMES += ekfstatevariance
|
||||
UAVOBJSRCFILENAMES += revocalibration
|
||||
UAVOBJSRCFILENAMES += revosettings
|
||||
UAVOBJSRCFILENAMES += sonaraltitude
|
||||
UAVOBJSRCFILENAMES += stabilizationdesired
|
||||
UAVOBJSRCFILENAMES += stabilizationsettings
|
||||
UAVOBJSRCFILENAMES += stabilizationsettingsbank1
|
||||
UAVOBJSRCFILENAMES += stabilizationsettingsbank2
|
||||
UAVOBJSRCFILENAMES += stabilizationsettingsbank3
|
||||
UAVOBJSRCFILENAMES += stabilizationstatus
|
||||
UAVOBJSRCFILENAMES += stabilizationbank
|
||||
UAVOBJSRCFILENAMES += systemalarms
|
||||
UAVOBJSRCFILENAMES += systemsettings
|
||||
UAVOBJSRCFILENAMES += systemstats
|
||||
UAVOBJSRCFILENAMES += taskinfo
|
||||
UAVOBJSRCFILENAMES += callbackinfo
|
||||
UAVOBJSRCFILENAMES += velocitystate
|
||||
UAVOBJSRCFILENAMES += velocitydesired
|
||||
UAVOBJSRCFILENAMES += watchdogstatus
|
||||
UAVOBJSRCFILENAMES += flightstatus
|
||||
UAVOBJSRCFILENAMES += hwsettings
|
||||
UAVOBJSRCFILENAMES += receiveractivity
|
||||
UAVOBJSRCFILENAMES += receiverstatus
|
||||
UAVOBJSRCFILENAMES += cameradesired
|
||||
UAVOBJSRCFILENAMES += camerastabsettings
|
||||
UAVOBJSRCFILENAMES += altitudeholdsettings
|
||||
UAVOBJSRCFILENAMES += oplinksettings
|
||||
UAVOBJSRCFILENAMES += oplinkstatus
|
||||
UAVOBJSRCFILENAMES += altitudefiltersettings
|
||||
UAVOBJSRCFILENAMES += altitudeholdstatus
|
||||
UAVOBJSRCFILENAMES += waypoint
|
||||
UAVOBJSRCFILENAMES += waypointactive
|
||||
UAVOBJSRCFILENAMES += poilocation
|
||||
UAVOBJSRCFILENAMES += poilearnsettings
|
||||
UAVOBJSRCFILENAMES += mpugyroaccelsettings
|
||||
UAVOBJSRCFILENAMES += txpidsettings
|
||||
UAVOBJSRCFILENAMES += txpidstatus
|
||||
UAVOBJSRCFILENAMES += takeofflocation
|
||||
UAVOBJSRCFILENAMES += perfcounter
|
||||
UAVOBJSRCFILENAMES += systemidentsettings
|
||||
UAVOBJSRCFILENAMES += systemidentstate
|
||||
UAVOBJSRCFILENAMES += cameracontrolsettings
|
||||
UAVOBJSRCFILENAMES += cameracontrolactivity
|
||||
|
||||
UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(FLIGHT_UAVOBJ_DIR)/$(UAVOBJSRCFILE).c )
|
||||
UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) )
|
93
flight/targets/boards/ccf3d/firmware/cm3_fault_handlers.c
Normal file
93
flight/targets/boards/ccf3d/firmware/cm3_fault_handlers.c
Normal file
@ -0,0 +1,93 @@
|
||||
/*
|
||||
* 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 (;;) {
|
||||
;
|
||||
}
|
||||
}
|
98
flight/targets/boards/ccf3d/firmware/coptercontrol.cpp
Normal file
98
flight/targets/boards/ccf3d/firmware/coptercontrol.cpp
Normal file
@ -0,0 +1,98 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup LibrePilotSystem LibrePilot System
|
||||
* @brief These files are the core system files for CopterControl.
|
||||
* They are the ground layer just above PiOS. In practice, CopterControl actually starts
|
||||
* in the main() function of coptercontrol.c
|
||||
* @{
|
||||
* @addtogroup LibrePilotCore LibrePilot Core
|
||||
* @brief This is where the LP firmware starts. Those files also define the compile-time
|
||||
* options of the firmware.
|
||||
* @{
|
||||
* @file coptercontrol.c
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
|
||||
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2015
|
||||
* @brief Sets up and runs main tasks.
|
||||
* @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
|
||||
*/
|
||||
|
||||
extern "C" {
|
||||
#include "inc/openpilot.h"
|
||||
#include <systemmod.h>
|
||||
/* Task Priorities */
|
||||
|
||||
/* Global Variables */
|
||||
extern void Stack_Change(void);
|
||||
} /* extern "C" */
|
||||
|
||||
/**
|
||||
* OpenPilot Main function:
|
||||
*
|
||||
* Initialize PiOS<BR>
|
||||
* Create the "System" task (SystemModInitializein Modules/System/systemmod.c) <BR>
|
||||
* Start FreeRTOS Scheduler (vTaskStartScheduler) (Now handled by caller)
|
||||
* If something goes wrong, blink LED1 and LED2 every 100ms
|
||||
*
|
||||
*/
|
||||
int main()
|
||||
{
|
||||
/* NOTE: Do NOT modify the following start-up sequence */
|
||||
/* Any new initialization functions should be added in OpenPilotInit() */
|
||||
|
||||
vPortInitialiseBlocks();
|
||||
|
||||
/* Brings up System using CMSIS functions, enables the LEDs. */
|
||||
PIOS_SYS_Init();
|
||||
|
||||
|
||||
SystemModStart();
|
||||
|
||||
/* Start the FreeRTOS scheduler, which should never return.
|
||||
*
|
||||
* NOTE: OpenPilot runs an operating system (FreeRTOS), which constantly calls
|
||||
* (schedules) function files (modules). These functions never return from their
|
||||
* while loops, which explains why each module has a while(1){} segment. Thus,
|
||||
* the OpenPilot software actually starts at the vTaskStartScheduler() function,
|
||||
* even though this is somewhat obscure.
|
||||
*
|
||||
* In addition, there are many main() functions in the OpenPilot firmware source tree
|
||||
* This is because each main() refers to a separate hardware platform. Of course,
|
||||
* C only allows one main(), so only the relevant main() function is compiled when
|
||||
* making a specific firmware.
|
||||
*
|
||||
*/
|
||||
vTaskStartScheduler();
|
||||
|
||||
/* If all is well we will never reach here as the scheduler will now be running. */
|
||||
|
||||
/* Do some indication to user that something bad just happened */
|
||||
while (1) {
|
||||
#if defined(PIOS_LED_HEARTBEAT)
|
||||
PIOS_LED_Toggle(PIOS_LED_HEARTBEAT);
|
||||
#endif /* PIOS_LED_HEARTBEAT */
|
||||
PIOS_DELAY_WaitmS(100);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
149
flight/targets/boards/ccf3d/firmware/dcc_stdio.c
Normal file
149
flight/targets/boards/ccf3d/firmware/dcc_stdio.c
Normal file
@ -0,0 +1,149 @@
|
||||
/***************************************************************************
|
||||
* 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]);
|
||||
}
|
||||
}
|
99
flight/targets/boards/ccf3d/firmware/inc/FreeRTOSConfig.h
Normal file
99
flight/targets/boards/ccf3d/firmware/inc/FreeRTOSConfig.h
Normal file
@ -0,0 +1,99 @@
|
||||
#ifndef FREERTOS_CONFIG_H
|
||||
#define FREERTOS_CONFIG_H
|
||||
|
||||
/*-----------------------------------------------------------
|
||||
* Application specific definitions.
|
||||
*
|
||||
* These definitions should be adjusted for your particular hardware and
|
||||
* application requirements.
|
||||
*
|
||||
* THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE
|
||||
* FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE.
|
||||
*
|
||||
* See http://www.freertos.org/a00110.html.
|
||||
*----------------------------------------------------------*/
|
||||
|
||||
/**
|
||||
* @addtogroup PIOS PIOS
|
||||
* @{
|
||||
* @addtogroup FreeRTOS FreeRTOS
|
||||
* @{
|
||||
*/
|
||||
|
||||
/* Notes: We use 5 task priorities */
|
||||
|
||||
#define configUSE_PREEMPTION 1
|
||||
#define configUSE_IDLE_HOOK 1
|
||||
#define configUSE_TICK_HOOK 0
|
||||
#define configUSE_MALLOC_FAILED_HOOK 1
|
||||
#define configCPU_CLOCK_HZ ((unsigned long)72000000)
|
||||
#define configTICK_RATE_HZ ((portTickType)1000)
|
||||
#define configMAX_PRIORITIES ((unsigned portBASE_TYPE)5)
|
||||
#define configMINIMAL_STACK_SIZE ((unsigned short)512)
|
||||
#define configTOTAL_HEAP_SIZE ((size_t)(53 * 256))
|
||||
#define configMAX_TASK_NAME_LEN (6)
|
||||
#define configUSE_TRACE_FACILITY 0
|
||||
#define configUSE_16_BIT_TICKS 0
|
||||
#define configIDLE_SHOULD_YIELD 0
|
||||
#define configUSE_MUTEXES 1
|
||||
#define configUSE_RECURSIVE_MUTEXES 1
|
||||
#define configUSE_COUNTING_SEMAPHORES 0
|
||||
#define configUSE_ALTERNATIVE_API 0
|
||||
#define configQUEUE_REGISTRY_SIZE 0
|
||||
|
||||
/* Co-routine definitions. */
|
||||
#define configUSE_CO_ROUTINES 0
|
||||
#define configMAX_CO_ROUTINE_PRIORITIES (2)
|
||||
|
||||
/* Set the following definitions to 1 to include the API function, or zero
|
||||
to exclude the API function. */
|
||||
|
||||
#define INCLUDE_vTaskPrioritySet 1
|
||||
#define INCLUDE_uxTaskPriorityGet 1
|
||||
#define INCLUDE_vTaskDelete 1
|
||||
#define INCLUDE_vTaskCleanUpResources 0
|
||||
#define INCLUDE_vTaskSuspend 1
|
||||
#define INCLUDE_vTaskDelayUntil 1
|
||||
#define INCLUDE_vTaskDelay 1
|
||||
#define INCLUDE_xTaskGetSchedulerState 0
|
||||
#define INCLUDE_xTaskGetCurrentTaskHandle 1
|
||||
#define INCLUDE_uxTaskGetStackHighWaterMark 1
|
||||
|
||||
/* This is the raw value as per the Cortex-M3 NVIC. Values can be 255
|
||||
(lowest) to 1 (highest maskable) to 0 (highest non-maskable). */
|
||||
#define configKERNEL_INTERRUPT_PRIORITY 15 << 4 /* equivalent to NVIC priority 15 */
|
||||
#define configMAX_SYSCALL_INTERRUPT_PRIORITY 3 << 4 /* equivalent to NVIC priority 3 */
|
||||
|
||||
/* This is the value being used as per the ST library which permits 16
|
||||
priority values, 0 to 15. This must correspond to the
|
||||
configKERNEL_INTERRUPT_PRIORITY setting. Here 15 corresponds to the lowest
|
||||
NVIC value of 255. */
|
||||
#define configLIBRARY_KERNEL_INTERRUPT_PRIORITY 15
|
||||
|
||||
#if !defined(ARCH_POSIX) && !defined(ARCH_WIN32)
|
||||
#define CHECK_IRQ_STACK
|
||||
#endif
|
||||
|
||||
/* Enable run time stats collection */
|
||||
#define configGENERATE_RUN_TIME_STATS 1
|
||||
#define INCLUDE_uxTaskGetRunTime 1
|
||||
#define INCLUDE_xTaskGetIdleTaskHandle 1
|
||||
#define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() \
|
||||
do { \
|
||||
(*(unsigned long *)0xe000edfc) |= (1 << 24); /* DEMCR |= DEMCR_TRCENA */ \
|
||||
(*(unsigned long *)0xe0001000) |= 1; /* DWT_CTRL |= DWT_CYCCNT_ENA */ \
|
||||
} \
|
||||
while (0)
|
||||
#define portGET_RUN_TIME_COUNTER_VALUE() (*(unsigned long *)0xe0001004) /* DWT_CYCCNT */
|
||||
|
||||
#ifdef DIAG_TASKS
|
||||
#define configCHECK_FOR_STACK_OVERFLOW 2
|
||||
#else
|
||||
#define configCHECK_FOR_STACK_OVERFLOW 1
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
||||
#endif /* FREERTOS_CONFIG_H */
|
36
flight/targets/boards/ccf3d/firmware/inc/dcc_stdio.h
Normal file
36
flight/targets/boards/ccf3d/firmware/inc/dcc_stdio.h
Normal file
@ -0,0 +1,36 @@
|
||||
/***************************************************************************
|
||||
* 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 */
|
52
flight/targets/boards/ccf3d/firmware/inc/openpilot.h
Normal file
52
flight/targets/boards/ccf3d/firmware/inc/openpilot.h
Normal file
@ -0,0 +1,52 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotSystem OpenPilot System
|
||||
* @{
|
||||
* @addtogroup OpenPilotCore OpenPilot Core
|
||||
* @{
|
||||
* @file openpilot.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Main OpenPilot 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
|
||||
*/
|
||||
|
||||
#ifndef OPENPILOT_H
|
||||
#define OPENPILOT_H
|
||||
|
||||
/* PIOS Includes */
|
||||
#include <pios.h>
|
||||
|
||||
/* OpenPilot Libraries */
|
||||
#include <utlist.h>
|
||||
#include <uavobjectmanager.h>
|
||||
#include <eventdispatcher.h>
|
||||
#include <uavtalk.h>
|
||||
|
||||
#include "alarms.h"
|
||||
#include <mathmisc.h>
|
||||
|
||||
/* Global Functions */
|
||||
void OpenPilotInit(void);
|
||||
|
||||
#endif /* OPENPILOT_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
81
flight/targets/boards/ccf3d/firmware/inc/pios_board_posix.h
Normal file
81
flight/targets/boards/ccf3d/firmware/inc/pios_board_posix.h
Normal file
@ -0,0 +1,81 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pios_board.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Defines board hardware for the OpenPilot Version 1.1 hardware.
|
||||
* @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
|
||||
*/
|
||||
|
||||
|
||||
#ifndef PIOS_BOARD_H
|
||||
#define PIOS_BOARD_H
|
||||
|
||||
|
||||
// ------------------------
|
||||
// PIOS_LED
|
||||
// ------------------------
|
||||
// #define PIOS_LED_LED1_GPIO_PORT GPIOC
|
||||
// #define PIOS_LED_LED1_GPIO_PIN GPIO_Pin_12
|
||||
// #define PIOS_LED_LED1_GPIO_CLK RCC_APB2Periph_GPIOC
|
||||
// #define PIOS_LED_LED2_GPIO_PORT GPIOC
|
||||
// #define PIOS_LED_LED2_GPIO_PIN GPIO_Pin_13
|
||||
// #define PIOS_LED_LED2_GPIO_CLK RCC_APB2Periph_GPIOC
|
||||
#define PIOS_LED_NUM 2
|
||||
// #define PIOS_LED_PORTS { PIOS_LED_LED1_GPIO_PORT, PIOS_LED_LED2_GPIO_PORT }
|
||||
// #define PIOS_LED_PINS { PIOS_LED_LED1_GPIO_PIN, PIOS_LED_LED2_GPIO_PIN }
|
||||
// #define PIOS_LED_CLKS { PIOS_LED_LED1_GPIO_CLK, PIOS_LED_LED2_GPIO_CLK }
|
||||
|
||||
|
||||
// -------------------------
|
||||
// COM
|
||||
//
|
||||
// See also pios_board_posix.c
|
||||
// -------------------------
|
||||
// #define PIOS_USART_TX_BUFFER_SIZE 256
|
||||
#define PIOS_COM_BUFFER_SIZE 1024
|
||||
#define PIOS_UDP_RX_BUFFER_SIZE PIOS_COM_BUFFER_SIZE
|
||||
|
||||
#define PIOS_COM_TELEM_RF 0
|
||||
#define PIOS_COM_GPS 1
|
||||
#define PIOS_COM_TELEM_USB 2
|
||||
|
||||
#ifdef PIOS_ENABLE_AUX_UART
|
||||
#define PIOS_COM_AUX 3
|
||||
#define PIOS_COM_DEBUG PIOS_COM_AUX
|
||||
#endif
|
||||
|
||||
/**
|
||||
* glue macros for file IO
|
||||
* STM32 uses DOSFS for file IO
|
||||
*/
|
||||
#define PIOS_FOPEN_READ(filename, file) (file = fopen((char *)filename, "r")) == NULL
|
||||
|
||||
#define PIOS_FOPEN_WRITE(filename, file) (file = fopen((char *)filename, "w")) == NULL
|
||||
|
||||
#define PIOS_FREAD(file, bufferadr, length, resultadr) (*resultadr = fread((uint8_t *)bufferadr, 1, length, *file)) != length
|
||||
|
||||
#define PIOS_FWRITE(file, bufferadr, length, resultadr) *resultadr = fwrite((uint8_t *)bufferadr, 1, length, *file)
|
||||
|
||||
|
||||
#define PIOS_FCLOSE(file) fclose(file)
|
||||
|
||||
#define PIOS_FUNLINK(file) unlink((char *)filename)
|
||||
|
||||
#endif /* PIOS_BOARD_H */
|
189
flight/targets/boards/ccf3d/firmware/inc/pios_config.h
Normal file
189
flight/targets/boards/ccf3d/firmware/inc/pios_config.h
Normal file
@ -0,0 +1,189 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotSystem OpenPilot System
|
||||
* @{
|
||||
* @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
|
||||
* @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
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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_CONFIG_H
|
||||
#define PIOS_CONFIG_H
|
||||
|
||||
/*
|
||||
* Below is a complete list of PIOS configurable options.
|
||||
* Please do not remove or rearrange them. Only comment out
|
||||
* unused options in the list. See main pios.h header for more
|
||||
* details.
|
||||
*/
|
||||
|
||||
/* #define PIOS_INCLUDE_DEBUG_CONSOLE */
|
||||
/* #define DEBUG_LEVEL 0 */
|
||||
/* #define PIOS_ENABLE_DEBUG_PINS */
|
||||
|
||||
/* PIOS FreeRTOS support */
|
||||
#define PIOS_INCLUDE_FREERTOS
|
||||
|
||||
|
||||
/* PIOS CallbackScheduler support */
|
||||
#define PIOS_INCLUDE_CALLBACKSCHEDULER
|
||||
|
||||
/* PIOS bootloader helper */
|
||||
#define PIOS_INCLUDE_BL_HELPER
|
||||
/* #define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT */
|
||||
|
||||
/* PIOS system functions */
|
||||
#define PIOS_INCLUDE_DELAY
|
||||
#define PIOS_INCLUDE_INITCALL
|
||||
#define PIOS_INCLUDE_SYS
|
||||
#define PIOS_INCLUDE_TASK_MONITOR
|
||||
// #define PIOS_INCLUDE_INSTRUMENTATION
|
||||
#define PIOS_INSTRUMENTATION_MAX_COUNTERS 5
|
||||
|
||||
/* PIOS hardware peripherals */
|
||||
#define PIOS_INCLUDE_IRQ
|
||||
#define PIOS_INCLUDE_RTC
|
||||
#define PIOS_INCLUDE_TIM
|
||||
#define PIOS_INCLUDE_USART
|
||||
/* #define PIOS_INCLUDE_ADC */
|
||||
#define PIOS_INCLUDE_I2C
|
||||
#define PIOS_INCLUDE_SPI
|
||||
#define PIOS_INCLUDE_GPIO
|
||||
#define PIOS_INCLUDE_EXTI
|
||||
#define PIOS_INCLUDE_WDG
|
||||
|
||||
/* PIOS USB functions */
|
||||
#define PIOS_INCLUDE_USB
|
||||
#define PIOS_INCLUDE_USB_HID
|
||||
#define PIOS_INCLUDE_USB_CDC
|
||||
/* #define PIOS_INCLUDE_USB_RCTX */
|
||||
|
||||
/* PIOS sensor interfaces */
|
||||
/* #define PIOS_INCLUDE_ADXL345 */
|
||||
/* #define PIOS_INCLUDE_BMA180 */
|
||||
/* #define PIOS_INCLUDE_L3GD20 */
|
||||
#define PIOS_INCLUDE_MPU6000
|
||||
#define PIOS_MPU6000_ACCEL
|
||||
/* #define PIOS_INCLUDE_HMC5843 */
|
||||
/* #define PIOS_INCLUDE_HMC5X83 */
|
||||
/* #define PIOS_HMC5883_HAS_GPIOS */
|
||||
/* #define PIOS_INCLUDE_BMP085 */
|
||||
/* #define PIOS_INCLUDE_MS5611 */
|
||||
/* #define PIOS_INCLUDE_MPXV */
|
||||
/* #define PIOS_INCLUDE_ETASV3 */
|
||||
/* #define PIOS_INCLUDE_HCSR04 */
|
||||
|
||||
#define PIOS_SENSOR_RATE 500.0f
|
||||
|
||||
/* PIOS receiver drivers */
|
||||
#define PIOS_INCLUDE_PWM
|
||||
#define PIOS_INCLUDE_PPM
|
||||
#define PIOS_INCLUDE_PPM_FLEXI
|
||||
#define PIOS_INCLUDE_DSM
|
||||
#define PIOS_INCLUDE_SBUS
|
||||
#define PIOS_INCLUDE_EXBUS
|
||||
#define PIOS_INCLUDE_SRXL
|
||||
#define PIOS_INCLUDE_HOTT
|
||||
#define PIOS_INCLUDE_IBUS
|
||||
/* #define PIOS_INCLUDE_GCSRCVR */
|
||||
/* #define PIOS_INCLUDE_OPLINKRCVR */
|
||||
|
||||
/* PIOS abstract receiver interface */
|
||||
#define PIOS_INCLUDE_RCVR
|
||||
|
||||
/* PIOS common peripherals */
|
||||
#define PIOS_INCLUDE_LED
|
||||
#define PIOS_INCLUDE_IAP
|
||||
#define PIOS_INCLUDE_SERVO
|
||||
/* #define PIOS_INCLUDE_I2C_ESC */
|
||||
/* #define PIOS_INCLUDE_OVERO */
|
||||
/* #define PIOS_OVERO_SPI */
|
||||
/* #define PIOS_INCLUDE_SDCARD */
|
||||
/* #define LOG_FILENAME "startup.log" */
|
||||
#define PIOS_INCLUDE_FLASH
|
||||
#define PIOS_INCLUDE_FLASH_LOGFS_SETTINGS
|
||||
/* #define FLASH_FREERTOS */
|
||||
/* #define PIOS_INCLUDE_FLASH_EEPROM */
|
||||
/* #define PIOS_INCLUDE_FLASH_INTERNAL */
|
||||
|
||||
/* PIOS radio modules */
|
||||
/* #define PIOS_INCLUDE_RFM22B */
|
||||
/* #define PIOS_INCLUDE_RFM22B_COM */
|
||||
/* #define PIOS_INCLUDE_PPM_OUT */
|
||||
/* #define PIOS_RFM22B_DEBUG_ON_TELEM */
|
||||
|
||||
/* PIOS misc peripherals */
|
||||
/* #define PIOS_INCLUDE_VIDEO */
|
||||
/* #define PIOS_INCLUDE_WAVE */
|
||||
/* #define PIOS_INCLUDE_UDP */
|
||||
|
||||
/* PIOS abstract comms interface with options */
|
||||
#define PIOS_INCLUDE_COM
|
||||
/* #define PIOS_INCLUDE_COM_MSG */
|
||||
#define PIOS_INCLUDE_TELEMETRY_RF
|
||||
/* #define PIOS_INCLUDE_COM_TELEM */
|
||||
/* #define PIOS_INCLUDE_COM_FLEXI */
|
||||
/* #define PIOS_INCLUDE_COM_AUX */
|
||||
/* #define PIOS_TELEM_PRIORITY_QUEUE */
|
||||
#define PIOS_INCLUDE_GPS
|
||||
/* #define PIOS_GPS_MINIMAL */
|
||||
#define PIOS_INCLUDE_GPS_NMEA_PARSER
|
||||
#define PIOS_INCLUDE_GPS_UBX_PARSER
|
||||
#define PIOS_INCLUDE_GPS_DJI_PARSER
|
||||
#define PIOS_GPS_SETS_HOMELOCATION
|
||||
|
||||
/* Stabilization options */
|
||||
#define PIOS_QUATERNION_STABILIZATION
|
||||
/* #define PIOS_EXCLUDE_ADVANCED_FEATURES */
|
||||
/* Performance counters */
|
||||
#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD 1995998
|
||||
|
||||
/* Alarm Thresholds */
|
||||
#define HEAP_LIMIT_WARNING 220
|
||||
#define HEAP_LIMIT_CRITICAL 40
|
||||
#define IRQSTACK_LIMIT_WARNING 100
|
||||
#define IRQSTACK_LIMIT_CRITICAL 60
|
||||
#define CPULOAD_LIMIT_WARNING 85
|
||||
#define CPULOAD_LIMIT_CRITICAL 95
|
||||
|
||||
/* Task stack sizes */
|
||||
#define PIOS_ACTUATOR_STACK_SIZE 800
|
||||
#define PIOS_MANUAL_STACK_SIZE 935
|
||||
#define PIOS_RECEIVER_STACK_SIZE 840
|
||||
#define PIOS_SYSTEM_STACK_SIZE 1536
|
||||
/* #define PIOS_STABILIZATION_STACK_SIZE 400 */
|
||||
|
||||
#define PIOS_TELEM_STACK_SIZE 800
|
||||
#define PIOS_EVENTDISPATCHER_STACK_SIZE 256
|
||||
|
||||
/* This can't be too high to stop eventdispatcher thread overflowing */
|
||||
#define PIOS_EVENTDISAPTCHER_QUEUE 10
|
||||
|
||||
/* Revolution series */
|
||||
#define REVOLUTION
|
||||
|
||||
#endif /* PIOS_CONFIG_H */
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
48
flight/targets/boards/ccf3d/firmware/inc/pios_config_posix.h
Normal file
48
flight/targets/boards/ccf3d/firmware/inc/pios_config_posix.h
Normal file
@ -0,0 +1,48 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pios_config.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief PiOS configuration header.
|
||||
* Central compile time config for the project.
|
||||
* @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
|
||||
*/
|
||||
|
||||
|
||||
#ifndef PIOS_CONFIG_POSIX_H
|
||||
#define PIOS_CONFIG_POSIX_H
|
||||
|
||||
|
||||
/* Enable/Disable PiOS Modules */
|
||||
#define PIOS_INCLUDE_SYS
|
||||
#define PIOS_INCLUDE_DELAY
|
||||
#define PIOS_INCLUDE_LED
|
||||
#define PIOS_INCLUDE_FREERTOS
|
||||
#define PIOS_INCLUDE_CALLBACKSCHEDULER
|
||||
#define PIOS_INCLUDE_TASK_MONITOR
|
||||
#define PIOS_INCLUDE_COM
|
||||
#define PIOS_INCLUDE_UDP
|
||||
#define PIOS_INCLUDE_SERVO
|
||||
|
||||
|
||||
/* Defaults for Logging */
|
||||
#define LOG_FILENAME "PIOS.LOG"
|
||||
#define STARTUP_LOG_ENABLED 1
|
||||
|
||||
#endif /* PIOS_CONFIG_POSIX_H */
|
@ -0,0 +1,47 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_USB_BOARD Board specific USB definitions
|
||||
* @brief Board specific USB definitions
|
||||
* @{
|
||||
*
|
||||
* @file pios_usb_board_data.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Board specific USB definitions
|
||||
* @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
|
||||
*/
|
||||
|
||||
#ifndef PIOS_USB_BOARD_DATA_H
|
||||
#define PIOS_USB_BOARD_DATA_H
|
||||
|
||||
// Note : changing below length will require changes to the USB buffer setup
|
||||
#define PIOS_USB_BOARD_CDC_DATA_LENGTH 64
|
||||
#define PIOS_USB_BOARD_CDC_MGMT_LENGTH 32
|
||||
#define PIOS_USB_BOARD_HID_DATA_LENGTH 64
|
||||
|
||||
#define PIOS_USB_BOARD_EP_NUM 4
|
||||
|
||||
#include <pios_usb_defs.h> /* USB_* macros */
|
||||
|
||||
#define PIOS_USB_BOARD_PRODUCT_ID USB_PRODUCT_ID_COPTERCONTROL
|
||||
#define PIOS_USB_BOARD_DEVICE_VER USB_OP_DEVICE_VER(USB_OP_BOARD_ID_COPTERCONTROL, USB_OP_BOARD_MODE_FW)
|
||||
#define PIOS_USB_BOARD_SN_SUFFIX "+FW"
|
||||
|
||||
#endif /* PIOS_USB_BOARD_DATA_H */
|
343
flight/targets/boards/ccf3d/firmware/pios_board.c
Normal file
343
flight/targets/boards/ccf3d/firmware/pios_board.c
Normal file
@ -0,0 +1,343 @@
|
||||
/**
|
||||
*****************************************************************************
|
||||
* @file pios_board.c
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
|
||||
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* PhoenixPilot, http://github.com/PhoenixPilot, Copyright (C) 2012
|
||||
* @addtogroup LibrePilotSystem LibrePilot System
|
||||
* @{
|
||||
* @addtogroup LibrePilotCore LibrePilot Core
|
||||
* @{
|
||||
* @brief Defines board specific static initializers for hardware for the CopterControl board.
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 "inc/openpilot.h"
|
||||
#include <pios_board_info.h>
|
||||
#include <uavobjectsinit.h>
|
||||
#include <hwsettings.h>
|
||||
#include <manualcontrolsettings.h>
|
||||
#include <gcsreceiver.h>
|
||||
#include <taskinfo.h>
|
||||
#include <sanitycheck.h>
|
||||
#include <actuatorsettings.h>
|
||||
#include <auxmagsettings.h>
|
||||
|
||||
#ifdef PIOS_INCLUDE_INSTRUMENTATION
|
||||
#include <pios_instrumentation.h>
|
||||
#endif
|
||||
|
||||
#include <pios_board_io.h>
|
||||
#include <pios_board_sensors.h>
|
||||
|
||||
/*
|
||||
* Pull in the board-specific static HW definitions.
|
||||
* Including .c files is a bit ugly but this allows all of
|
||||
* the HW definitions to be const and static to limit their
|
||||
* scope.
|
||||
*
|
||||
* NOTE: THIS IS THE ONLY PLACE THAT SHOULD EVER INCLUDE THIS FILE
|
||||
*/
|
||||
#include "../board_hw_defs.c"
|
||||
|
||||
|
||||
static SystemAlarmsExtendedAlarmStatusOptions CopterControlConfigHook();
|
||||
static void ActuatorSettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev);
|
||||
|
||||
uintptr_t pios_uavo_settings_fs_id;
|
||||
uintptr_t pios_user_fs_id = 0;
|
||||
|
||||
/**
|
||||
* PIOS_Board_Init()
|
||||
* initializes all the core subsystems on this specific hardware
|
||||
* called from System/openpilot.c
|
||||
*/
|
||||
int32_t init_test;
|
||||
void PIOS_Board_Init(void)
|
||||
{
|
||||
const struct pios_board_info *bdinfo = &pios_board_info_blob;
|
||||
|
||||
#if defined(PIOS_INCLUDE_LED)
|
||||
const struct pios_gpio_cfg *led_cfg = PIOS_BOARD_HW_DEFS_GetLedCfg(bdinfo->board_rev);
|
||||
PIOS_Assert(led_cfg);
|
||||
PIOS_LED_Init(led_cfg);
|
||||
#endif /* PIOS_INCLUDE_LED */
|
||||
|
||||
#ifdef PIOS_INCLUDE_INSTRUMENTATION
|
||||
PIOS_Instrumentation_Init(PIOS_INSTRUMENTATION_MAX_COUNTERS);
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_SPI)
|
||||
/* Set up the SPI interface to the serial flash */
|
||||
if (PIOS_SPI_Init(&pios_spi_flash_accel_id, &pios_spi_flash_accel_cfg_cc3d)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
#endif
|
||||
|
||||
uintptr_t flash_id;
|
||||
if (PIOS_Flash_Jedec_Init(&flash_id, pios_spi_flash_accel_id, 0)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
if (PIOS_FLASHFS_Logfs_Init(&pios_uavo_settings_fs_id, &flashfs_m25p_cfg, &pios_jedec_flash_driver, flash_id)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
|
||||
/* Initialize the task monitor */
|
||||
if (PIOS_TASK_MONITOR_Initialize(TASKINFO_RUNNING_NUMELEM)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
/* Initialize the delayed callback library */
|
||||
PIOS_CALLBACKSCHEDULER_Initialize();
|
||||
|
||||
/* Initialize UAVObject libraries */
|
||||
EventDispatcherInitialize();
|
||||
UAVObjInitialize();
|
||||
|
||||
#if defined(PIOS_INCLUDE_RTC)
|
||||
/* Initialize the real-time clock and its associated tick */
|
||||
PIOS_RTC_Init(&pios_rtc_main_cfg);
|
||||
#endif
|
||||
PIOS_IAP_Init();
|
||||
// check for safe mode commands from gcs
|
||||
if (PIOS_IAP_ReadBootCmd(0) == PIOS_IAP_CLEAR_FLASH_CMD_0 &&
|
||||
PIOS_IAP_ReadBootCmd(1) == PIOS_IAP_CLEAR_FLASH_CMD_1 &&
|
||||
PIOS_IAP_ReadBootCmd(2) == PIOS_IAP_CLEAR_FLASH_CMD_2) {
|
||||
PIOS_FLASHFS_Format(pios_uavo_settings_fs_id);
|
||||
PIOS_IAP_WriteBootCmd(0, 0);
|
||||
PIOS_IAP_WriteBootCmd(1, 0);
|
||||
PIOS_IAP_WriteBootCmd(2, 0);
|
||||
}
|
||||
|
||||
HwSettingsInitialize();
|
||||
|
||||
#ifndef ERASE_FLASH
|
||||
#ifdef PIOS_INCLUDE_WDG
|
||||
/* Initialize watchdog as early as possible to catch faults during init */
|
||||
PIOS_WDG_Init();
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/* Initialize the alarms library */
|
||||
AlarmsInitialize();
|
||||
|
||||
/* Check for repeated boot failures */
|
||||
uint16_t boot_count = PIOS_IAP_ReadBootCount();
|
||||
if (boot_count < 3) {
|
||||
PIOS_IAP_WriteBootCount(++boot_count);
|
||||
AlarmsClear(SYSTEMALARMS_ALARM_BOOTFAULT);
|
||||
} else {
|
||||
/* Too many failed boot attempts, force hwsettings to defaults */
|
||||
HwSettingsSetDefaults(HwSettingsHandle(), 0);
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT, SYSTEMALARMS_ALARM_CRITICAL);
|
||||
}
|
||||
|
||||
/* Set up pulse timers */
|
||||
PIOS_TIM_InitClock(&tim_1_cfg);
|
||||
PIOS_TIM_InitClock(&tim_2_cfg);
|
||||
PIOS_TIM_InitClock(&tim_3_cfg);
|
||||
PIOS_TIM_InitClock(&tim_4_cfg);
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB)
|
||||
PIOS_BOARD_IO_Configure_USB();
|
||||
#endif
|
||||
|
||||
/* Configure the main IO port */
|
||||
static const PIOS_BOARD_IO_UART_Function usart_main_function_map[] = {
|
||||
[HWSETTINGS_CC_MAINPORT_TELEMETRY] = PIOS_BOARD_IO_UART_TELEMETRY,
|
||||
[HWSETTINGS_CC_MAINPORT_GPS] = PIOS_BOARD_IO_UART_GPS,
|
||||
[HWSETTINGS_CC_MAINPORT_SBUS] = PIOS_BOARD_IO_UART_SBUS,
|
||||
[HWSETTINGS_CC_MAINPORT_DSM] = PIOS_BOARD_IO_UART_DSM_MAIN,
|
||||
[HWSETTINGS_CC_MAINPORT_DEBUGCONSOLE] = PIOS_BOARD_IO_UART_DEBUGCONSOLE,
|
||||
[HWSETTINGS_CC_MAINPORT_COMBRIDGE] = PIOS_BOARD_IO_UART_COMBRIDGE,
|
||||
[HWSETTINGS_CC_MAINPORT_OSDHK] = PIOS_BOARD_IO_UART_OSDHK,
|
||||
[HWSETTINGS_CC_MAINPORT_MSP] = PIOS_BOARD_IO_UART_MSP,
|
||||
[HWSETTINGS_CC_MAINPORT_MAVLINK] = PIOS_BOARD_IO_UART_MAVLINK,
|
||||
};
|
||||
|
||||
uint8_t hwsettings_cc_mainport;
|
||||
HwSettingsCC_MainPortGet(&hwsettings_cc_mainport);
|
||||
|
||||
if(hwsettings_cc_mainport < NELEMENTS(usart_main_function_map)) {
|
||||
PIOS_BOARD_IO_Configure_UART(&pios_usart_main_cfg, usart_main_function_map[hwsettings_cc_mainport]);
|
||||
}
|
||||
|
||||
|
||||
/* Configure the flexi port */
|
||||
static const PIOS_BOARD_IO_UART_Function usart_flexi_function_map[] = {
|
||||
[HWSETTINGS_CC_FLEXIPORT_TELEMETRY] = PIOS_BOARD_IO_UART_TELEMETRY,
|
||||
[HWSETTINGS_CC_FLEXIPORT_GPS] = PIOS_BOARD_IO_UART_GPS,
|
||||
[HWSETTINGS_CC_FLEXIPORT_DSM] = PIOS_BOARD_IO_UART_DSM_FLEXI,
|
||||
[HWSETTINGS_CC_FLEXIPORT_EXBUS] = PIOS_BOARD_IO_UART_EXBUS,
|
||||
[HWSETTINGS_CC_FLEXIPORT_HOTTSUMD] = PIOS_BOARD_IO_UART_HOTT_SUMD,
|
||||
[HWSETTINGS_CC_FLEXIPORT_HOTTSUMH] = PIOS_BOARD_IO_UART_HOTT_SUMH,
|
||||
[HWSETTINGS_CC_FLEXIPORT_SRXL] = PIOS_BOARD_IO_UART_SRXL,
|
||||
[HWSETTINGS_CC_FLEXIPORT_IBUS] = PIOS_BOARD_IO_UART_IBUS,
|
||||
[HWSETTINGS_CC_FLEXIPORT_DEBUGCONSOLE] = PIOS_BOARD_IO_UART_DEBUGCONSOLE,
|
||||
[HWSETTINGS_CC_FLEXIPORT_COMBRIDGE] = PIOS_BOARD_IO_UART_COMBRIDGE,
|
||||
[HWSETTINGS_CC_FLEXIPORT_OSDHK] = PIOS_BOARD_IO_UART_OSDHK,
|
||||
[HWSETTINGS_CC_FLEXIPORT_MSP] = PIOS_BOARD_IO_UART_MSP,
|
||||
[HWSETTINGS_CC_FLEXIPORT_MAVLINK] = PIOS_BOARD_IO_UART_MAVLINK,
|
||||
};
|
||||
|
||||
uint8_t hwsettings_cc_flexiport;
|
||||
HwSettingsCC_FlexiPortGet(&hwsettings_cc_flexiport);
|
||||
|
||||
if(hwsettings_cc_flexiport < NELEMENTS(usart_flexi_function_map)) {
|
||||
PIOS_BOARD_IO_Configure_UART(&pios_usart_flexi_cfg, usart_flexi_function_map[hwsettings_cc_flexiport]);
|
||||
}
|
||||
|
||||
if(hwsettings_cc_flexiport == HWSETTINGS_CC_FLEXIPORT_PPM) {
|
||||
#if defined(PIOS_INCLUDE_PPM_FLEXI)
|
||||
PIOS_BOARD_IO_Configure_PPM_RCVR(&pios_ppm_flexi_cfg);
|
||||
#endif /* PIOS_INCLUDE_PPM_FLEXI */
|
||||
} else if(hwsettings_cc_flexiport == HWSETTINGS_CC_FLEXIPORT_I2C) {
|
||||
// F303CC has no I2C on CC3D flexi.
|
||||
}
|
||||
|
||||
/* Configure the rcvr port */
|
||||
uint8_t hwsettings_rcvrport;
|
||||
HwSettingsCC_RcvrPortGet(&hwsettings_rcvrport);
|
||||
|
||||
switch ((HwSettingsCC_RcvrPortOptions)hwsettings_rcvrport) {
|
||||
case HWSETTINGS_CC_RCVRPORT_DISABLEDONESHOT:
|
||||
#if defined(PIOS_INCLUDE_HCSR04)
|
||||
{
|
||||
uint32_t pios_hcsr04_id;
|
||||
PIOS_HCSR04_Init(&pios_hcsr04_id, &pios_hcsr04_cfg);
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
case HWSETTINGS_CC_RCVRPORT_PWMNOONESHOT:
|
||||
#if defined(PIOS_INCLUDE_PWM)
|
||||
PIOS_BOARD_IO_Configure_PWM_RCVR(&pios_pwm_cfg);
|
||||
#endif /* PIOS_INCLUDE_PWM */
|
||||
break;
|
||||
case HWSETTINGS_CC_RCVRPORT_PPM_PIN8ONESHOT:
|
||||
#if defined(PIOS_INCLUDE_PPM)
|
||||
PIOS_BOARD_IO_Configure_PPM_RCVR(&pios_ppm_pin8_cfg);
|
||||
#endif /* PIOS_INCLUDE_PPM */
|
||||
break;
|
||||
case HWSETTINGS_CC_RCVRPORT_PPMNOONESHOT:
|
||||
case HWSETTINGS_CC_RCVRPORT_PPMOUTPUTSNOONESHOT:
|
||||
#if defined(PIOS_INCLUDE_PPM)
|
||||
PIOS_BOARD_IO_Configure_PPM_RCVR(&pios_ppm_cfg);
|
||||
#endif /* PIOS_INCLUDE_PPM */
|
||||
break;
|
||||
case HWSETTINGS_CC_RCVRPORT_PPMPWMNOONESHOT:
|
||||
/* This is a combination of PPM and PWM inputs */
|
||||
#if defined(PIOS_INCLUDE_PPM)
|
||||
PIOS_BOARD_IO_Configure_PPM_RCVR(&pios_ppm_cfg);
|
||||
#endif /* PIOS_INCLUDE_PPM */
|
||||
#if defined(PIOS_INCLUDE_PWM)
|
||||
PIOS_BOARD_IO_Configure_PWM_RCVR(&pios_pwm_with_ppm_cfg);
|
||||
#endif /* PIOS_INCLUDE_PWM */
|
||||
break;
|
||||
case HWSETTINGS_CC_RCVRPORT_OUTPUTSONESHOT:
|
||||
break;
|
||||
}
|
||||
|
||||
|
||||
|
||||
#if defined(PIOS_INCLUDE_GCSRCVR)
|
||||
PIOS_BOARD_IO_Configure_GCSRCVR();
|
||||
#endif /* PIOS_INCLUDE_GCSRCVR */
|
||||
|
||||
#ifndef PIOS_ENABLE_DEBUG_PINS
|
||||
switch ((HwSettingsCC_RcvrPortOptions)hwsettings_rcvrport) {
|
||||
case HWSETTINGS_CC_RCVRPORT_DISABLEDONESHOT:
|
||||
case HWSETTINGS_CC_RCVRPORT_PWMNOONESHOT:
|
||||
case HWSETTINGS_CC_RCVRPORT_PPMNOONESHOT:
|
||||
case HWSETTINGS_CC_RCVRPORT_PPMPWMNOONESHOT:
|
||||
case HWSETTINGS_CC_RCVRPORT_PPM_PIN8ONESHOT:
|
||||
PIOS_Servo_Init(&pios_servo_cfg);
|
||||
break;
|
||||
case HWSETTINGS_CC_RCVRPORT_PPMOUTPUTSNOONESHOT:
|
||||
case HWSETTINGS_CC_RCVRPORT_OUTPUTSONESHOT:
|
||||
PIOS_Servo_Init(&pios_servo_rcvr_cfg);
|
||||
break;
|
||||
}
|
||||
#else
|
||||
PIOS_DEBUG_Init(pios_tim_servoport_all_pins, NELEMENTS(pios_tim_servoport_all_pins));
|
||||
#endif /* PIOS_ENABLE_DEBUG_PINS */
|
||||
|
||||
PIOS_BOARD_Sensors_Configure();
|
||||
|
||||
/* Make sure we have at least one telemetry link configured or else fail initialization */
|
||||
PIOS_Assert(pios_com_telem_rf_id || pios_com_telem_usb_id);
|
||||
|
||||
// Attach the board config check hook
|
||||
SANITYCHECK_AttachHook(&CopterControlConfigHook);
|
||||
// trigger a config check if actuatorsettings are updated
|
||||
ActuatorSettingsInitialize();
|
||||
ActuatorSettingsConnectCallback(ActuatorSettingsUpdatedCb);
|
||||
}
|
||||
|
||||
SystemAlarmsExtendedAlarmStatusOptions CopterControlConfigHook()
|
||||
{
|
||||
// inhibit usage of oneshot for non supported RECEIVER port modes
|
||||
uint8_t recmode;
|
||||
|
||||
HwSettingsCC_RcvrPortGet(&recmode);
|
||||
uint8_t flexiMode;
|
||||
uint8_t modes[ACTUATORSETTINGS_BANKMODE_NUMELEM];
|
||||
ActuatorSettingsBankModeGet(modes);
|
||||
HwSettingsCC_FlexiPortGet(&flexiMode);
|
||||
|
||||
switch ((HwSettingsCC_RcvrPortOptions)recmode) {
|
||||
// Those modes allows oneshot usage
|
||||
case HWSETTINGS_CC_RCVRPORT_DISABLEDONESHOT:
|
||||
case HWSETTINGS_CC_RCVRPORT_OUTPUTSONESHOT:
|
||||
case HWSETTINGS_CC_RCVRPORT_PPM_PIN8ONESHOT:
|
||||
if ((recmode == HWSETTINGS_CC_RCVRPORT_PPM_PIN8ONESHOT ||
|
||||
flexiMode == HWSETTINGS_CC_FLEXIPORT_PPM) &&
|
||||
(modes[3] == ACTUATORSETTINGS_BANKMODE_PWMSYNC ||
|
||||
modes[3] == ACTUATORSETTINGS_BANKMODE_ONESHOT125 ||
|
||||
modes[3] == ACTUATORSETTINGS_BANKMODE_ONESHOT42 ||
|
||||
modes[3] == ACTUATORSETTINGS_BANKMODE_MULTISHOT)) {
|
||||
return SYSTEMALARMS_EXTENDEDALARMSTATUS_UNSUPPORTEDCONFIG_ONESHOT;
|
||||
} else {
|
||||
return SYSTEMALARMS_EXTENDEDALARMSTATUS_NONE;
|
||||
}
|
||||
|
||||
// inhibit oneshot for the following modes
|
||||
case HWSETTINGS_CC_RCVRPORT_PPMNOONESHOT:
|
||||
case HWSETTINGS_CC_RCVRPORT_PPMOUTPUTSNOONESHOT:
|
||||
case HWSETTINGS_CC_RCVRPORT_PPMPWMNOONESHOT:
|
||||
case HWSETTINGS_CC_RCVRPORT_PWMNOONESHOT:
|
||||
for (uint8_t i = 0; i < ACTUATORSETTINGS_BANKMODE_NUMELEM; i++) {
|
||||
if (modes[i] == ACTUATORSETTINGS_BANKMODE_PWMSYNC ||
|
||||
modes[i] == ACTUATORSETTINGS_BANKMODE_ONESHOT125 ||
|
||||
modes[i] == ACTUATORSETTINGS_BANKMODE_ONESHOT42 ||
|
||||
modes[i] == ACTUATORSETTINGS_BANKMODE_MULTISHOT) {
|
||||
return SYSTEMALARMS_EXTENDEDALARMSTATUS_UNSUPPORTEDCONFIG_ONESHOT;;
|
||||
}
|
||||
|
||||
return SYSTEMALARMS_EXTENDEDALARMSTATUS_NONE;
|
||||
}
|
||||
}
|
||||
return SYSTEMALARMS_EXTENDEDALARMSTATUS_UNSUPPORTEDCONFIG_ONESHOT;;
|
||||
}
|
||||
// trigger a configuration check if ActuatorSettings are changed.
|
||||
void ActuatorSettingsUpdatedCb(__attribute__((unused)) UAVObjEvent *ev)
|
||||
{
|
||||
configuration_check();
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
145
flight/targets/boards/ccf3d/firmware/pios_board_posix.c
Normal file
145
flight/targets/boards/ccf3d/firmware/pios_board_posix.c
Normal file
@ -0,0 +1,145 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pios_board.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Defines board specific static initializers for hardware for the OpenPilot board.
|
||||
* @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 "inc/openpilot.h"
|
||||
#include <pios_udp_priv.h>
|
||||
#include <pios_com_priv.h>
|
||||
#include <uavobjectsinit.h>
|
||||
|
||||
/**
|
||||
* PIOS_Board_Init()
|
||||
* initializes all the core systems on this specific hardware
|
||||
* called from System/openpilot.c
|
||||
*/
|
||||
void PIOS_Board_Init(void)
|
||||
{
|
||||
/* Delay system */
|
||||
PIOS_DELAY_Init();
|
||||
|
||||
/* Initialize the delayed callback library */
|
||||
PIOS_CALLBACKSCHEDULER_Initialize();
|
||||
|
||||
/* Initialize UAVObject libraries */
|
||||
EventDispatcherInitialize();
|
||||
UAVObjInitialize();
|
||||
|
||||
/* Initialize the alarms library */
|
||||
AlarmsInitialize();
|
||||
|
||||
/* Initialize the task monitor */
|
||||
if (PIOS_TASK_MONITOR_Initialize(TASKINFO_RUNNING_NUMELEM)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
/* Initialize the PiOS library */
|
||||
PIOS_COM_Init();
|
||||
}
|
||||
|
||||
|
||||
const struct pios_udp_cfg pios_udp0_cfg = {
|
||||
.ip = "0.0.0.0",
|
||||
.port = 9000,
|
||||
};
|
||||
const struct pios_udp_cfg pios_udp1_cfg = {
|
||||
.ip = "0.0.0.0",
|
||||
.port = 9001,
|
||||
};
|
||||
const struct pios_udp_cfg pios_udp2_cfg = {
|
||||
.ip = "0.0.0.0",
|
||||
.port = 9002,
|
||||
};
|
||||
|
||||
#ifdef PIOS_COM_AUX
|
||||
/*
|
||||
* AUX USART
|
||||
*/
|
||||
const struct pios_udp_cfg pios_udp3_cfg = {
|
||||
.ip = "0.0.0.0",
|
||||
.port = 9003,
|
||||
};
|
||||
#endif
|
||||
|
||||
/*
|
||||
* Board specific number of devices.
|
||||
*/
|
||||
struct pios_udp_dev pios_udp_devs[] = {
|
||||
#define PIOS_UDP_TELEM 0
|
||||
{
|
||||
.cfg = &pios_udp0_cfg,
|
||||
},
|
||||
#define PIOS_UDP_GPS 1
|
||||
{
|
||||
.cfg = &pios_udp1_cfg,
|
||||
},
|
||||
#define PIOS_UDP_LOCAL 2
|
||||
{
|
||||
.cfg = &pios_udp2_cfg,
|
||||
},
|
||||
#ifdef PIOS_COM_AUX
|
||||
#define PIOS_UDP_AUX 3
|
||||
{
|
||||
.cfg = &pios_udp3_cfg,
|
||||
},
|
||||
#endif
|
||||
};
|
||||
|
||||
uint8_t pios_udp_num_devices = NELEMENTS(pios_udp_devs);
|
||||
|
||||
/*
|
||||
* COM devices
|
||||
*/
|
||||
|
||||
/*
|
||||
* Board specific number of devices.
|
||||
*/
|
||||
extern const struct pios_com_driver pios_serial_com_driver;
|
||||
extern const struct pios_com_driver pios_udp_com_driver;
|
||||
|
||||
struct pios_com_dev pios_com_devs[] = {
|
||||
{
|
||||
.id = PIOS_UDP_TELEM,
|
||||
.driver = &pios_udp_com_driver,
|
||||
},
|
||||
{
|
||||
.id = PIOS_UDP_GPS,
|
||||
.driver = &pios_udp_com_driver,
|
||||
},
|
||||
{
|
||||
.id = PIOS_UDP_LOCAL,
|
||||
.driver = &pios_udp_com_driver,
|
||||
},
|
||||
#ifdef PIOS_COM_AUX
|
||||
{
|
||||
.id = PIOS_UDP_AUX,
|
||||
.driver = &pios_udp_com_driver,
|
||||
},
|
||||
#endif
|
||||
};
|
||||
|
||||
const uint8_t pios_com_num_devices = NELEMENTS(pios_com_devs);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
312
flight/targets/boards/ccf3d/pios_board.h
Normal file
312
flight/targets/boards/ccf3d/pios_board.h
Normal file
@ -0,0 +1,312 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pios_board.h
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
|
||||
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
*
|
||||
* @brief Defines board hardware for the OpenPilot Version 1.1 hardware.
|
||||
* @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
|
||||
*/
|
||||
|
||||
#ifndef PIOS_BOARD_H
|
||||
#define PIOS_BOARD_H
|
||||
// ------------------------
|
||||
// Timers and Channels Used
|
||||
// ------------------------
|
||||
/*
|
||||
Timer | Channel 1 | Channel 2 | Channel 3 | Channel 4
|
||||
------+-----------+-----------+-----------+----------
|
||||
TIM1 | Servo 4 | | |
|
||||
TIM2 | RC In 5 | RC In 6 | Servo 6 |
|
||||
TIM3 | Servo 5 | RC In 2 | RC In 3 | RC In 4
|
||||
TIM4 | RC In 1 | Servo 3 | Servo 2 | Servo 1
|
||||
------+-----------+-----------+-----------+----------
|
||||
*/
|
||||
|
||||
// ------------------------
|
||||
// DMA Channels Used
|
||||
// ------------------------
|
||||
/* Channel 1 - */
|
||||
/* Channel 2 - */
|
||||
/* Channel 3 - */
|
||||
/* Channel 4 - */
|
||||
/* Channel 5 - */
|
||||
/* Channel 6 - */
|
||||
/* Channel 7 - */
|
||||
/* Channel 8 - */
|
||||
/* Channel 9 - */
|
||||
/* Channel 10 - */
|
||||
/* Channel 11 - */
|
||||
/* Channel 12 - */
|
||||
|
||||
// ------------------------
|
||||
// BOOTLOADER_SETTINGS
|
||||
// ------------------------
|
||||
#define BOARD_READABLE true
|
||||
#define BOARD_WRITABLE true
|
||||
#define MAX_DEL_RETRYS 3
|
||||
|
||||
// ------------------------
|
||||
// WATCHDOG_SETTINGS
|
||||
// ------------------------
|
||||
#define PIOS_WATCHDOG_TIMEOUT 250
|
||||
#define PIOS_WDG_REGISTER RTC_BKP_DR4
|
||||
#define PIOS_WDG_ACTUATOR 0x0001
|
||||
#define PIOS_WDG_STABILIZATION 0x0002
|
||||
#define PIOS_WDG_ATTITUDE 0x0004
|
||||
#define PIOS_WDG_MANUAL 0x0008
|
||||
#define PIOS_WDG_AUTOTUNE 0x0010
|
||||
#define PIOS_WDG_SENSORS 0x0020
|
||||
|
||||
|
||||
// ------------------------
|
||||
// TELEMETRY
|
||||
// ------------------------
|
||||
#define TELEM_QUEUE_SIZE 10
|
||||
|
||||
// ------------------------
|
||||
// PIOS_LED
|
||||
// ------------------------
|
||||
#define PIOS_LED_HEARTBEAT 0
|
||||
|
||||
// -------------------------
|
||||
// System Settings
|
||||
// -------------------------
|
||||
#define PIOS_MASTER_CLOCK 72000000
|
||||
#define PIOS_PERIPHERAL_CLOCK (PIOS_MASTER_CLOCK / 2)
|
||||
|
||||
// -------------------------
|
||||
// Interrupt Priorities
|
||||
// -------------------------
|
||||
#define PIOS_IRQ_PRIO_LOW 12 // lower than RTOS
|
||||
#define PIOS_IRQ_PRIO_MID 8 // higher than RTOS
|
||||
#define PIOS_IRQ_PRIO_HIGH 5 // for SPI, ADC, I2C etc...
|
||||
#define PIOS_IRQ_PRIO_HIGHEST 4 // for USART etc...
|
||||
// ------------------------
|
||||
// PIOS_I2C
|
||||
// See also pios_board.c
|
||||
// ------------------------
|
||||
#define PIOS_I2C_MAX_DEVS 1
|
||||
#define PIOS_I2C_EXTERNAL_ADAPTER (0)
|
||||
#define PIOS_I2C_FLEXI_ADAPTER (0)
|
||||
|
||||
// ------------------------
|
||||
// PIOS_BMP085
|
||||
// ------------------------
|
||||
#define PIOS_BMP085_OVERSAMPLING 3
|
||||
|
||||
// -------------------------
|
||||
// SPI
|
||||
//
|
||||
// See also pios_board.c
|
||||
// -------------------------
|
||||
#define PIOS_SPI_MAX_DEVS 2
|
||||
extern uint32_t pios_spi_gyro_id;
|
||||
#define PIOS_SPI_MPU6000_ADAPTER (pios_spi_gyro_id)
|
||||
// -------------------------
|
||||
// PIOS_USART
|
||||
// -------------------------
|
||||
#define PIOS_USART_MAX_DEVS 2
|
||||
|
||||
// -------------------------
|
||||
// PIOS_COM
|
||||
//
|
||||
// See also pios_board.c
|
||||
// -------------------------
|
||||
#define PIOS_COM_MAX_DEVS 3
|
||||
|
||||
extern uint32_t pios_com_telem_rf_id;
|
||||
#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id)
|
||||
|
||||
#if defined(PIOS_INCLUDE_GPS)
|
||||
extern uint32_t pios_com_gps_id;
|
||||
#define PIOS_COM_GPS (pios_com_gps_id)
|
||||
#endif /* PIOS_INCLUDE_GPS */
|
||||
|
||||
extern uint32_t pios_com_bridge_id;
|
||||
#define PIOS_COM_BRIDGE (pios_com_bridge_id)
|
||||
|
||||
extern uint32_t pios_com_vcp_id;
|
||||
#define PIOS_COM_VCP (pios_com_vcp_id)
|
||||
|
||||
extern uint32_t pios_com_telem_usb_id;
|
||||
#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id)
|
||||
|
||||
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
|
||||
extern uint32_t pios_com_debug_id;
|
||||
#define PIOS_COM_DEBUG (pios_com_debug_id)
|
||||
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
|
||||
|
||||
extern uint32_t pios_com_hkosd_id;
|
||||
#define PIOS_COM_OSDHK (pios_com_hkosd_id)
|
||||
|
||||
extern uint32_t pios_com_msp_id;
|
||||
#define PIOS_COM_MSP (pios_com_msp_id)
|
||||
|
||||
extern uint32_t pios_com_mavlink_id;
|
||||
#define PIOS_COM_MAVLINK (pios_com_mavlink_id)
|
||||
|
||||
// -------------------------
|
||||
// ADC
|
||||
// PIOS_ADC_PinGet(0) = Gyro Z
|
||||
// PIOS_ADC_PinGet(1) = Gyro Y
|
||||
// PIOS_ADC_PinGet(2) = Gyro X
|
||||
// -------------------------
|
||||
// #define PIOS_ADC_OVERSAMPLING_RATE 1
|
||||
#define PIOS_ADC_USE_TEMP_SENSOR 1
|
||||
#define PIOS_ADC_TEMP_SENSOR_ADC ADC1
|
||||
#define PIOS_ADC_TEMP_SENSOR_ADC_CHANNEL 1
|
||||
|
||||
#define PIOS_ADC_PIN1_GPIO_PORT GPIOA // PA4 (Gyro X)
|
||||
#define PIOS_ADC_PIN1_GPIO_PIN GPIO_Pin_4 // ADC12_IN4
|
||||
#define PIOS_ADC_PIN1_GPIO_CHANNEL ADC_Channel_4
|
||||
#define PIOS_ADC_PIN1_ADC ADC2
|
||||
#define PIOS_ADC_PIN1_ADC_NUMBER 1
|
||||
|
||||
#define PIOS_ADC_PIN2_GPIO_PORT GPIOA // PA5 (Gyro Y)
|
||||
#define PIOS_ADC_PIN2_GPIO_PIN GPIO_Pin_5 // ADC123_IN5
|
||||
#define PIOS_ADC_PIN2_GPIO_CHANNEL ADC_Channel_5
|
||||
#define PIOS_ADC_PIN2_ADC ADC1
|
||||
#define PIOS_ADC_PIN2_ADC_NUMBER 2
|
||||
|
||||
#define PIOS_ADC_PIN3_GPIO_PORT GPIOA // PA3 (Gyro Z)
|
||||
#define PIOS_ADC_PIN3_GPIO_PIN GPIO_Pin_3 // ADC12_IN3
|
||||
#define PIOS_ADC_PIN3_GPIO_CHANNEL ADC_Channel_3
|
||||
#define PIOS_ADC_PIN3_ADC ADC2
|
||||
#define PIOS_ADC_PIN3_ADC_NUMBER 2
|
||||
|
||||
#define PIOS_ADC_NUM_PINS 3
|
||||
|
||||
#define PIOS_ADC_PORTS { PIOS_ADC_PIN1_GPIO_PORT, PIOS_ADC_PIN2_GPIO_PORT, PIOS_ADC_PIN3_GPIO_PORT }
|
||||
#define PIOS_ADC_PINS { PIOS_ADC_PIN1_GPIO_PIN, PIOS_ADC_PIN2_GPIO_PIN, PIOS_ADC_PIN3_GPIO_PIN }
|
||||
#define PIOS_ADC_CHANNELS { PIOS_ADC_PIN1_GPIO_CHANNEL, PIOS_ADC_PIN2_GPIO_CHANNEL, PIOS_ADC_PIN3_GPIO_CHANNEL }
|
||||
#define PIOS_ADC_MAPPING { PIOS_ADC_PIN1_ADC, PIOS_ADC_PIN2_ADC, PIOS_ADC_PIN3_ADC }
|
||||
#define PIOS_ADC_CHANNEL_MAPPING { PIOS_ADC_PIN1_ADC_NUMBER, PIOS_ADC_PIN2_ADC_NUMBER, PIOS_ADC_PIN3_ADC_NUMBER }
|
||||
#define PIOS_ADC_NUM_CHANNELS (PIOS_ADC_NUM_PINS + PIOS_ADC_USE_TEMP_SENSOR)
|
||||
#define PIOS_ADC_NUM_ADC_CHANNELS 2
|
||||
#define PIOS_ADC_USE_ADC2 1
|
||||
#define PIOS_ADC_CLOCK_FUNCTION RCC_AHBPeriphClockCmd(RCC_AHBPeriph_ADC12, ENABLE)
|
||||
#define PIOS_ADC_ADCCLK RCC_ADC12PLLCLK_Div32
|
||||
/* RCC_PCLK2_Div2: ADC clock = PCLK2/2 */
|
||||
/* RCC_PCLK2_Div4: ADC clock = PCLK2/4 */
|
||||
/* RCC_PCLK2_Div6: ADC clock = PCLK2/6 */
|
||||
/* RCC_PCLK2_Div8: ADC clock = PCLK2/8 */
|
||||
#define PIOS_ADC_SAMPLE_TIME ADC_SampleTime_181Cycles5
|
||||
/* Sample time: */
|
||||
/* With an ADCCLK = 14 MHz and a sampling time of 239.5 cycles: */
|
||||
/* Tconv = 239.5 + 12.5 = 252 cycles = 18<31>s */
|
||||
/* (1 / (ADCCLK / CYCLES)) = Sample Time (<28>S) */
|
||||
#define PIOS_ADC_IRQ_PRIO PIOS_IRQ_PRIO_LOW
|
||||
|
||||
// Currently analog acquistion hard coded at 480 Hz
|
||||
// PCKL2 = HCLK / 16
|
||||
// ADCCLK = PCLK2 / 2
|
||||
#define PIOS_ADC_RATE (72.0e6f / 1.0f / 8.0f / 252.0f / (PIOS_ADC_NUM_CHANNELS >> PIOS_ADC_USE_ADC2))
|
||||
#define PIOS_ADC_MAX_OVERSAMPLING 48
|
||||
|
||||
#define PIOS_ADC_TEMPERATURE_PIN 0
|
||||
|
||||
// ------------------------
|
||||
// PIOS_RCVR
|
||||
// See also pios_board.c
|
||||
// ------------------------
|
||||
#define PIOS_RCVR_MAX_DEVS 3
|
||||
#define PIOS_RCVR_MAX_CHANNELS 12
|
||||
#define PIOS_GCSRCVR_TIMEOUT_MS 100
|
||||
|
||||
// -------------------------
|
||||
// Receiver PPM input
|
||||
// -------------------------
|
||||
#define PIOS_PPM_MAX_DEVS 1
|
||||
#define PIOS_PPM_NUM_INPUTS 16
|
||||
|
||||
// -------------------------
|
||||
// Receiver PWM input
|
||||
// -------------------------
|
||||
#define PIOS_PWM_MAX_DEVS 1
|
||||
#define PIOS_PWM_NUM_INPUTS 6
|
||||
|
||||
// -------------------------
|
||||
// Receiver DSM input
|
||||
// -------------------------
|
||||
#define PIOS_DSM_MAX_DEVS 2
|
||||
#define PIOS_DSM_NUM_INPUTS 12
|
||||
|
||||
// -------------------------
|
||||
// Receiver S.Bus input
|
||||
// -------------------------
|
||||
#define PIOS_SBUS_MAX_DEVS 1
|
||||
#define PIOS_SBUS_NUM_INPUTS (16 + 2)
|
||||
|
||||
// -------------------------
|
||||
// Receiver HOTT input
|
||||
// -------------------------
|
||||
#define PIOS_HOTT_MAX_DEVS 1
|
||||
#define PIOS_HOTT_NUM_INPUTS 32
|
||||
|
||||
// -------------------------
|
||||
// Receiver EX.Bus input
|
||||
// -------------------------
|
||||
#define PIOS_EXBUS_MAX_DEVS 1
|
||||
#define PIOS_EXBUS_NUM_INPUTS 16
|
||||
|
||||
// -------------------------
|
||||
// Receiver Multiplex SRXL input
|
||||
// -------------------------
|
||||
#define PIOS_SRXL_MAX_DEVS 1
|
||||
#define PIOS_SRXL_NUM_INPUTS 16
|
||||
|
||||
// -------------------------
|
||||
// Receiver FlySky IBus input
|
||||
// -------------------------
|
||||
#define PIOS_IBUS_MAX_DEVS 1
|
||||
#define PIOS_IBUS_NUM_INPUTS 10
|
||||
|
||||
// -------------------------
|
||||
// Servo outputs
|
||||
// -------------------------
|
||||
#define PIOS_SERVO_UPDATE_HZ 50
|
||||
#define PIOS_SERVOS_INITIAL_POSITION 0 /* dont want to start motors, have no pulse till settings loaded */
|
||||
#define PIOS_SERVO_BANKS 6
|
||||
|
||||
// --------------------------
|
||||
// Timer controller settings
|
||||
// --------------------------
|
||||
#define PIOS_TIM_MAX_DEVS 3
|
||||
|
||||
// -------------------------
|
||||
// GPIO
|
||||
// -------------------------
|
||||
#define PIOS_GPIO_PORTS {}
|
||||
#define PIOS_GPIO_PINS {}
|
||||
#define PIOS_GPIO_CLKS {}
|
||||
#define PIOS_GPIO_NUM 0
|
||||
|
||||
// -------------------------
|
||||
// USB
|
||||
// -------------------------
|
||||
#define PIOS_USB_HID_MAX_DEVS 1
|
||||
|
||||
#define PIOS_USB_ENABLED 1
|
||||
#define PIOS_USB_DETECT_GPIO_PORT GPIOC
|
||||
#define PIOS_USB_MAX_DEVS 1
|
||||
#define PIOS_USB_DETECT_GPIO_PIN GPIO_Pin_15
|
||||
|
||||
#endif /* PIOS_BOARD_H */
|
102
flight/targets/boards/ccf3d/pios_usb_board_data.c
Normal file
102
flight/targets/boards/ccf3d/pios_usb_board_data.c
Normal file
@ -0,0 +1,102 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_USB_BOARD Board specific USB definitions
|
||||
* @brief Board specific USB definitions
|
||||
* @{
|
||||
*
|
||||
* @file pios_usb_board_data.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Board specific USB definitions
|
||||
* @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 "inc/pios_usb_board_data.h" /* struct usb_*, USB_* */
|
||||
#include <pios_sys.h> /* PIOS_SYS_SerialNumberGet */
|
||||
#include <pios_usbhook.h> /* PIOS_USBHOOK_* */
|
||||
#include <pios_usb_util.h> /* PIOS_USB_UTIL_AsciiToUtf8 */
|
||||
|
||||
static const uint8_t usb_product_id[28] = {
|
||||
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,
|
||||
};
|
||||
|
||||
static uint8_t usb_serial_number[2 + PIOS_SYS_SERIAL_NUM_ASCII_LEN * 2 + (sizeof(PIOS_USB_BOARD_SN_SUFFIX) - 1) * 2] = {
|
||||
sizeof(usb_serial_number),
|
||||
USB_DESC_TYPE_STRING,
|
||||
};
|
||||
|
||||
static const struct usb_string_langid usb_lang_id = {
|
||||
.bLength = sizeof(usb_lang_id),
|
||||
.bDescriptorType = USB_DESC_TYPE_STRING,
|
||||
.bLangID = htousbs(USB_LANGID_ENGLISH_US),
|
||||
};
|
||||
|
||||
static const uint8_t usb_vendor_id[28] = {
|
||||
sizeof(usb_vendor_id),
|
||||
USB_DESC_TYPE_STRING,
|
||||
'o', 0,
|
||||
'p', 0,
|
||||
'e', 0,
|
||||
'n', 0,
|
||||
'p', 0,
|
||||
'i', 0,
|
||||
'l', 0,
|
||||
'o', 0,
|
||||
't', 0,
|
||||
'.', 0,
|
||||
'o', 0,
|
||||
'r', 0,
|
||||
'g', 0
|
||||
};
|
||||
|
||||
int32_t PIOS_USB_BOARD_DATA_Init(void)
|
||||
{
|
||||
/* Load device serial number into serial number string */
|
||||
uint8_t sn[PIOS_SYS_SERIAL_NUM_ASCII_LEN + 1];
|
||||
|
||||
PIOS_SYS_SerialNumberGet((char *)sn);
|
||||
|
||||
/* Concatenate the device serial number and the appropriate suffix ("+BL" or "+FW") into the USB serial number */
|
||||
uint8_t *utf8 = &(usb_serial_number[2]);
|
||||
utf8 = PIOS_USB_UTIL_AsciiToUtf8(utf8, sn, PIOS_SYS_SERIAL_NUM_ASCII_LEN);
|
||||
utf8 = PIOS_USB_UTIL_AsciiToUtf8(utf8, (uint8_t *)PIOS_USB_BOARD_SN_SUFFIX, sizeof(PIOS_USB_BOARD_SN_SUFFIX) - 1);
|
||||
|
||||
PIOS_USBHOOK_RegisterString(USB_STRING_DESC_PRODUCT, (uint8_t *)&usb_product_id, sizeof(usb_product_id));
|
||||
PIOS_USBHOOK_RegisterString(USB_STRING_DESC_SERIAL, (uint8_t *)&usb_serial_number, sizeof(usb_serial_number));
|
||||
|
||||
PIOS_USBHOOK_RegisterString(USB_STRING_DESC_LANG, (uint8_t *)&usb_lang_id, sizeof(usb_lang_id));
|
||||
PIOS_USBHOOK_RegisterString(USB_STRING_DESC_VENDOR, (uint8_t *)&usb_vendor_id, sizeof(usb_vendor_id));
|
||||
|
||||
return 0;
|
||||
}
|
@ -136,26 +136,6 @@ extern uint32_t pios_i2c_flexiport_adapter_id;
|
||||
// See also pios_board.c
|
||||
// -------------------------
|
||||
#define PIOS_COM_MAX_DEVS 4
|
||||
// extern uint32_t pios_com_telem_rf_id;
|
||||
// extern uint32_t pios_com_gps_id;
|
||||
// extern uint32_t pios_com_aux_id;
|
||||
// extern uint32_t pios_com_telem_usb_id;
|
||||
// extern uint32_t pios_com_bridge_id;
|
||||
// extern uint32_t pios_com_vcp_id;
|
||||
// extern uint32_t pios_com_hkosd_id;
|
||||
// extern uint32_t pios_com_msp_id;
|
||||
// extern uint32_t pios_com_mavlink_id;
|
||||
//
|
||||
// #define PIOS_COM_AUX (pios_com_aux_id)
|
||||
// #define PIOS_COM_GPS (pios_com_gps_id)
|
||||
// #define PIOS_COM_TELEM_USB (pios_com_telem_usb_id)
|
||||
// #define PIOS_COM_TELEM_RF (pios_com_telem_rf_id)
|
||||
// #define PIOS_COM_BRIDGE (pios_com_bridge_id)
|
||||
// #define PIOS_COM_VCP (pios_com_vcp_id)
|
||||
// #define PIOS_COM_DEBUG PIOS_COM_AUX
|
||||
// #define PIOS_COM_OSDHK (pios_com_hkosd_id)
|
||||
// #define PIOS_COM_MSP (pios_com_msp_id)
|
||||
// #define PIOS_COM_MAVLINK (pios_com_mavlink_id)
|
||||
|
||||
// ------------------------
|
||||
// TELEMETRY
|
||||
|
24
flight/targets/boards/spracingf3/board-info.mk
Normal file
24
flight/targets/boards/spracingf3/board-info.mk
Normal file
@ -0,0 +1,24 @@
|
||||
BOARD_TYPE := 0x10
|
||||
BOARD_REVISION := 0x01
|
||||
BOOTLOADER_VERSION := 0x00
|
||||
HW_TYPE := 0x01
|
||||
|
||||
MCU := cortex-m4
|
||||
PIOS_DEVLIB := $(PIOS)/stm32f30x
|
||||
CHIP := STM32F303xC
|
||||
BOARD := STM32F303CCT_SRF3_Rev1
|
||||
MODEL := HD
|
||||
|
||||
OPENOCD_JTAG_CONFIG := jlink.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
|
||||
|
||||
FW_BANK_BASE := 0x08004000 # Start of firmware flash
|
||||
FW_BANK_SIZE := 0x0003C000 # Should include FW_DESC_SIZE
|
||||
|
||||
FW_DESC_SIZE := 0x00000064
|
||||
|
||||
OSCILLATOR_FREQ := 8000000
|
832
flight/targets/boards/spracingf3/board_hw_defs.c
Normal file
832
flight/targets/boards/spracingf3/board_hw_defs.c
Normal file
@ -0,0 +1,832 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @file board_hw_defs.c
|
||||
* @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2015.
|
||||
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* PhoenixPilot, http://github.com/PhoenixPilot, Copyright (C) 2012
|
||||
*
|
||||
* @addtogroup OpenPilotSystem OpenPilot System
|
||||
* @{
|
||||
* @addtogroup OpenPilotCore OpenPilot Core
|
||||
* @{
|
||||
* @brief Defines board specific static initializers for hardware for the CopterControl board.
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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
|
||||
*/
|
||||
|
||||
#if defined(PIOS_INCLUDE_LED)
|
||||
|
||||
#include <pios_led_priv.h>
|
||||
|
||||
|
||||
static const struct pios_gpio pios_leds[] = {
|
||||
[PIOS_LED_HEARTBEAT] = {
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_3,
|
||||
.GPIO_Mode = GPIO_Mode_OUT,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL,
|
||||
},
|
||||
},
|
||||
// .remap = GPIO_Remap_SWJ_JTAGDisable,
|
||||
.active_low = false
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_gpio_cfg pios_led_cfg = {
|
||||
.gpios = pios_leds,
|
||||
.num_gpios = NELEMENTS(pios_leds),
|
||||
};
|
||||
|
||||
const struct pios_gpio_cfg *PIOS_BOARD_HW_DEFS_GetLedCfg(__attribute__((unused)) uint32_t board_revision)
|
||||
{
|
||||
return &pios_led_cfg;
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_LED */
|
||||
|
||||
#if defined(PIOS_INCLUDE_HMC5X83)
|
||||
#include "pios_hmc5x83.h"
|
||||
|
||||
#ifdef PIOS_HMC5X83_HAS_GPIOS
|
||||
bool pios_board_internal_mag_handler()
|
||||
{
|
||||
return PIOS_HMC5x83_IRQHandler(onboard_mag);
|
||||
}
|
||||
|
||||
static const struct pios_exti_cfg pios_exti_hmc5x83_cfg = {
|
||||
.vector = pios_board_internal_mag_handler,
|
||||
.line = EXTI_Line14,
|
||||
.pin = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_14,
|
||||
.GPIO_Speed = GPIO_Speed_100MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN,
|
||||
.GPIO_OType = GPIO_OType_OD,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL,
|
||||
},
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = EXTI15_10_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.exti = {
|
||||
.init = {
|
||||
.EXTI_Line = EXTI_Line14, // matches above GPIO pin
|
||||
.EXTI_Mode = EXTI_Mode_Interrupt,
|
||||
.EXTI_Trigger = EXTI_Trigger_Rising,
|
||||
.EXTI_LineCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
#endif /* PIOS_HMC5X83_HAS_GPIOS */
|
||||
|
||||
static const struct pios_hmc5x83_cfg pios_hmc5x83_internal_cfg = {
|
||||
#ifdef PIOS_HMC5X83_HAS_GPIOS
|
||||
.exti_cfg = &pios_exti_hmc5x83_cfg,
|
||||
#endif
|
||||
.M_ODR = PIOS_HMC5x83_ODR_75,
|
||||
.Meas_Conf = PIOS_HMC5x83_MEASCONF_NORMAL,
|
||||
.Gain = PIOS_HMC5x83_GAIN_1_9,
|
||||
.Mode = PIOS_HMC5x83_MODE_CONTINUOUS,
|
||||
.TempCompensation = false,
|
||||
.Driver = &PIOS_HMC5x83_I2C_DRIVER,
|
||||
.Orientation = PIOS_HMC5X83_ORIENTATION_EAST_NORTH_UP,
|
||||
};
|
||||
|
||||
static const struct pios_hmc5x83_cfg pios_hmc5x83_external_cfg = {
|
||||
#ifdef PIOS_HMC5X83_HAS_GPIOS
|
||||
.exti_cfg = NULL,
|
||||
#endif
|
||||
.M_ODR = PIOS_HMC5x83_ODR_75, // if you change this for auxmag, change AUX_MAG_SKIP in sensors.c
|
||||
.Meas_Conf = PIOS_HMC5x83_MEASCONF_NORMAL,
|
||||
.Gain = PIOS_HMC5x83_GAIN_1_9,
|
||||
.Mode = PIOS_HMC5x83_MODE_CONTINUOUS,
|
||||
.TempCompensation = false,
|
||||
.Driver = &PIOS_HMC5x83_I2C_DRIVER,
|
||||
.Orientation = PIOS_HMC5X83_ORIENTATION_EAST_NORTH_UP, // ENU for GPSV9, WND for typical I2C mag
|
||||
};
|
||||
const struct pios_hmc5x83_cfg *PIOS_BOARD_HW_DEFS_GetExternalHMC5x83Cfg(__attribute__((unused)) uint32_t board_revision)
|
||||
{
|
||||
return 0; // external HMC5883 will conflict with internal one.
|
||||
}
|
||||
const struct pios_hmc5x83_cfg *PIOS_BOARD_HW_DEFS_GetInternalHMC5x83Cfg(__attribute__((unused)) uint32_t board_revision)
|
||||
{
|
||||
return &pios_hmc5x83_internal_cfg;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_HMC5X83 */
|
||||
|
||||
/**
|
||||
* Configuration for the MS5611 chip
|
||||
*/
|
||||
#if defined(PIOS_INCLUDE_MS5611)
|
||||
#include "pios_ms5611.h"
|
||||
static const struct pios_ms5611_cfg pios_ms5611_cfg = {
|
||||
.oversampling = MS5611_OSR_4096,
|
||||
};
|
||||
const struct pios_ms5611_cfg *PIOS_BOARD_HW_DEFS_GetMS5611Cfg(__attribute__((unused)) uint32_t board_revision)
|
||||
{
|
||||
return &pios_ms5611_cfg;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_MS5611 */
|
||||
|
||||
|
||||
/**
|
||||
* Configuration for MPU6000 chip
|
||||
*/
|
||||
#if defined(PIOS_INCLUDE_MPU6000)
|
||||
#include "pios_mpu6000.h"
|
||||
static const struct pios_exti_cfg pios_exti_mpu6000_cfg __exti_config = {
|
||||
.vector = PIOS_MPU6000_IRQHandler,
|
||||
.line = EXTI_Line13,
|
||||
.pin = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_13,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN,
|
||||
.GPIO_OType = GPIO_OType_OD,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL,
|
||||
},
|
||||
},
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = EXTI15_10_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.exti = {
|
||||
.init = {
|
||||
.EXTI_Line = EXTI_Line13, // matches above GPIO pin
|
||||
.EXTI_Mode = EXTI_Mode_Interrupt,
|
||||
.EXTI_Trigger = EXTI_Trigger_Rising,
|
||||
.EXTI_LineCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_mpu6000_cfg pios_mpu6000_cfg = {
|
||||
.exti_cfg = &pios_exti_mpu6000_cfg,
|
||||
#ifdef PIOS_MPU6000_I2C_ADDR
|
||||
.i2c_addr = PIOS_MPU6000_I2C_ADDR,
|
||||
#endif
|
||||
.Fifo_store = PIOS_MPU6000_FIFO_TEMP_OUT | PIOS_MPU6000_FIFO_GYRO_X_OUT | PIOS_MPU6000_FIFO_GYRO_Y_OUT | PIOS_MPU6000_FIFO_GYRO_Z_OUT,
|
||||
// Clock at 8 khz, downsampled by 12 for 666Hz
|
||||
.Smpl_rate_div_no_dlp = 11,
|
||||
// Clock at 1 khz, downsampled by 1 for 1000 Hz
|
||||
.Smpl_rate_div_dlp = 0,
|
||||
.interrupt_cfg = PIOS_MPU6000_INT_CLR_ANYRD,
|
||||
.interrupt_en = PIOS_MPU6000_INTEN_DATA_RDY,
|
||||
.User_ctl = PIOS_MPU6000_USERCTL_FIFO_EN,
|
||||
.Pwr_mgmt_clk = PIOS_MPU6000_PWRMGMT_PLL_X_CLK,
|
||||
.accel_range = PIOS_MPU6000_ACCEL_8G,
|
||||
.gyro_range = PIOS_MPU6000_SCALE_2000_DEG,
|
||||
.filter = PIOS_MPU6000_LOWPASS_256_HZ,
|
||||
.orientation = PIOS_MPU6000_TOP_180DEG,
|
||||
};
|
||||
|
||||
const struct pios_mpu6000_cfg *PIOS_BOARD_HW_DEFS_GetMPU6000Cfg(__attribute__((unused)) uint32_t board_revision)
|
||||
{
|
||||
return &pios_mpu6000_cfg;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_MPU6000 */
|
||||
|
||||
|
||||
#if defined(PIOS_INCLUDE_SPI)
|
||||
|
||||
#include <pios_spi_priv.h>
|
||||
|
||||
/* Flash/Accel Interface
|
||||
*
|
||||
* NOTE: Leave this declared as const data so that it ends up in the
|
||||
* .rodata section (ie. Flash) rather than in the .bss section (RAM).
|
||||
*/
|
||||
void PIOS_SPI_flash_accel_irq_handler(void);
|
||||
void DMA1_Channel4_IRQHandler() __attribute__((alias("PIOS_SPI_flash_accel_irq_handler")));
|
||||
void DMA1_Channel5_IRQHandler() __attribute__((alias("PIOS_SPI_flash_accel_irq_handler")));
|
||||
static const struct pios_spi_cfg pios_spi_flash_accel_cfg = {
|
||||
.regs = SPI2,
|
||||
.init = {
|
||||
.SPI_Mode = SPI_Mode_Master,
|
||||
.SPI_Direction = SPI_Direction_2Lines_FullDuplex,
|
||||
.SPI_DataSize = SPI_DataSize_8b,
|
||||
.SPI_NSS = SPI_NSS_Soft,
|
||||
.SPI_FirstBit = SPI_FirstBit_MSB,
|
||||
.SPI_CRCPolynomial = 7,
|
||||
.SPI_CPOL = SPI_CPOL_High,
|
||||
.SPI_CPHA = SPI_CPHA_2Edge,
|
||||
.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_32,
|
||||
},
|
||||
.use_crc = false,
|
||||
.dma = {
|
||||
.ahb_clk = RCC_AHBPeriph_DMA1,
|
||||
|
||||
.irq = {
|
||||
.flags = (DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 | DMA1_FLAG_GL4),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Channel4_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
|
||||
.rx = {
|
||||
.channel = DMA1_Channel4,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI2->DR),
|
||||
.DMA_DIR = DMA_DIR_PeripheralSRC,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_High,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.channel = DMA1_Channel5,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI2->DR),
|
||||
.DMA_DIR = DMA_DIR_PeripheralDST,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_High,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
},
|
||||
.remap = GPIO_AF_5,
|
||||
.sclk = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_13,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL,
|
||||
},
|
||||
},
|
||||
.miso = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_14,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF, /* NOTE: was GPIO_Mode_IN_FLOATING */
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL,
|
||||
},
|
||||
},
|
||||
.mosi = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_15,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_NOPULL,
|
||||
},
|
||||
},
|
||||
.slave_count = 1,
|
||||
.ssel = {
|
||||
{
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_12,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_OUT,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP,
|
||||
}
|
||||
}, /*{
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_15,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_OUT,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP,
|
||||
},
|
||||
}*/
|
||||
},
|
||||
};
|
||||
|
||||
static uint32_t pios_spi_flash_accel_id;
|
||||
void PIOS_SPI_flash_accel_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_SPI_IRQ_Handler(pios_spi_flash_accel_id);
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_SPI */
|
||||
|
||||
#if defined(PIOS_INCLUDE_FLASH)
|
||||
#include "pios_flashfs_logfs_priv.h"
|
||||
#include "pios_flash_jedec_priv.h"
|
||||
|
||||
static const struct flashfs_logfs_cfg flashfs_w25x_cfg = {
|
||||
.fs_magic = 0x99abcdef,
|
||||
.total_fs_size = 0x00080000, /* 512K bytes (128 sectors = entire chip) */
|
||||
.arena_size = 0x00010000, /* 256 * slot size */
|
||||
.slot_size = 0x00000100, /* 256 bytes */
|
||||
|
||||
.start_offset = 0, /* start at the beginning of the chip */
|
||||
.sector_size = 0x00001000, /* 4K bytes */
|
||||
.page_size = 0x00000100, /* 256 bytes */
|
||||
};
|
||||
|
||||
|
||||
static const struct flashfs_logfs_cfg flashfs_m25p_cfg = {
|
||||
.fs_magic = 0x99abceef,
|
||||
.total_fs_size = 0x00200000, /* 2M bytes (32 sectors = entire chip) */
|
||||
.arena_size = 0x00010000, /* 256 * slot size */
|
||||
.slot_size = 0x00000100, /* 256 bytes */
|
||||
|
||||
.start_offset = 0, /* start at the beginning of the chip */
|
||||
.sector_size = 0x00010000, /* 64K bytes */
|
||||
.page_size = 0x00000100, /* 256 bytes */
|
||||
};
|
||||
|
||||
#include "pios_flash.h"
|
||||
|
||||
#endif /* PIOS_INCLUDE_FLASH */
|
||||
|
||||
#include "pios_tim_priv.h"
|
||||
|
||||
static const TIM_TimeBaseInitTypeDef tim_1_2_3_4_15_16_17_time_base = {
|
||||
.TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1,
|
||||
.TIM_ClockDivision = TIM_CKD_DIV1,
|
||||
.TIM_CounterMode = TIM_CounterMode_Up,
|
||||
.TIM_Period = ((1000000 / PIOS_SERVO_UPDATE_HZ) - 1),
|
||||
.TIM_RepetitionCounter = 0x0000,
|
||||
};
|
||||
|
||||
static const struct pios_tim_clock_cfg tim_1_cfg = {
|
||||
.timer = TIM1,
|
||||
.time_base_init = &tim_1_2_3_4_15_16_17_time_base,
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = TIM1_CC_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_tim_clock_cfg tim_2_cfg = {
|
||||
.timer = TIM2,
|
||||
.time_base_init = &tim_1_2_3_4_15_16_17_time_base,
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = TIM2_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_tim_clock_cfg tim_3_cfg = {
|
||||
.timer = TIM3,
|
||||
.time_base_init = &tim_1_2_3_4_15_16_17_time_base,
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = TIM3_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_tim_clock_cfg tim_4_cfg = {
|
||||
.timer = TIM4,
|
||||
.time_base_init = &tim_1_2_3_4_15_16_17_time_base,
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = TIM4_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_tim_clock_cfg tim_15_cfg = {
|
||||
.timer = TIM4,
|
||||
.time_base_init = &tim_1_2_3_4_15_16_17_time_base,
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = TIM1_BRK_TIM15_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_tim_clock_cfg tim_16_cfg = {
|
||||
.timer = TIM4,
|
||||
.time_base_init = &tim_1_2_3_4_15_16_17_time_base,
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = TIM1_UP_TIM16_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_tim_clock_cfg tim_17_cfg = {
|
||||
.timer = TIM4,
|
||||
.time_base_init = &tim_1_2_3_4_15_16_17_time_base,
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = TIM1_TRG_COM_TIM17_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
#include <pios_servo_config.h>
|
||||
|
||||
#define GPIO_AF_PA1_TIM2 GPIO_AF_1
|
||||
#define GPIO_AF_PA0_TIM2 GPIO_AF_1
|
||||
#define GPIO_AF_PA8_TIM1 GPIO_AF_6
|
||||
#define GPIO_AF_PA2_TIM2 GPIO_AF_1
|
||||
#define GPIO_AF_PB6_TIM4 GPIO_AF_2
|
||||
#define GPIO_AF_PB5_TIM3 GPIO_AF_2
|
||||
#define GPIO_AF_PB0_TIM3 GPIO_AF_2
|
||||
#define GPIO_AF_PB1_TIM3 GPIO_AF_2
|
||||
#define GPIO_AF_PB9_TIM4 GPIO_AF_2
|
||||
#define GPIO_AF_PB8_TIM4 GPIO_AF_2
|
||||
#define GPIO_AF_PB7_TIM4 GPIO_AF_2
|
||||
#define GPIO_AF_PB4_TIM3 GPIO_AF_2
|
||||
#define GPIO_AF_PB11_TIM2 GPIO_AF_1
|
||||
#define GPIO_AF_PB10_TIM2 GPIO_AF_1
|
||||
#define GPIO_AF_PA6_TIM16 GPIO_AF_1
|
||||
#define GPIO_AF_PA7_TIM17 GPIO_AF_1
|
||||
#define GPIO_AF_PA11_TIM4 GPIO_AF_10
|
||||
#define GPIO_AF_PA12_TIM4 GPIO_AF_10
|
||||
#define GPIO_AF_PA2_TIM15 GPIO_AF_9
|
||||
#define GPIO_AF_PA3_TIM15 GPIO_AF_9
|
||||
|
||||
|
||||
static const struct pios_tim_channel pios_tim_servoport_io1_io2_pins[] = {
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM16, 1, A, 6), // bank 1
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM17, 1, A, 7), // bank 1
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM4, 1, A, 11), // bank 1
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM4, 2, A, 12), // bank 2
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM4, 3, B, 8), // bank 3
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM4, 4, B, 9), // bank 4
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM15, 1, A, 2), // bank 1
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM15, 2, A, 3), // bank 2
|
||||
|
||||
// Receiver port pins
|
||||
// S3-S6 inputs are used as outputs in this case
|
||||
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM2, 1, A, 0),
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM2, 2, A, 1),
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM2, 4, B, 11),
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM2, 3, B, 10),
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM3, 1, B, 4),
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM3, 2, B, 5),
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM3, 3, B, 0),
|
||||
TIM_SERVO_CHANNEL_CONFIG(TIM3, 4, B, 1),
|
||||
};
|
||||
|
||||
#if defined(PIOS_INCLUDE_USART)
|
||||
|
||||
#define GPIO_AF_USART1 GPIO_AF_7
|
||||
#define GPIO_AF_USART2 GPIO_AF_7
|
||||
#define GPIO_AF_USART3 GPIO_AF_7
|
||||
|
||||
|
||||
#include "pios_usart_priv.h"
|
||||
#include "pios_usart_config.h"
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_cfg[] = {
|
||||
USART_CONFIG(USART1, A, 10, A, 9),
|
||||
USART_CONFIG(USART2, A, 15, A, 14),
|
||||
USART_CONFIG(USART3, B, 11, B, 10),
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_USART */
|
||||
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
|
||||
#include "pios_com_priv.h"
|
||||
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
|
||||
#if defined(PIOS_INCLUDE_RTC)
|
||||
/*
|
||||
* Realtime Clock (RTC)
|
||||
*/
|
||||
#include <pios_rtc_priv.h>
|
||||
|
||||
void PIOS_RTC_IRQ_Handler(void);
|
||||
void RTC_WKUP_IRQHandler() __attribute__((alias("PIOS_RTC_IRQ_Handler")));
|
||||
static const struct pios_rtc_cfg pios_rtc_main_cfg = {
|
||||
.clksrc = RCC_RTCCLKSource_HSE_Div32,
|
||||
.prescaler = 25 - 1, // 8Mhz / 32 / 16 / 25 => 625Hz
|
||||
.irq = {
|
||||
.init = {
|
||||
.NVIC_IRQChannel = RTC_WKUP_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
void PIOS_RTC_IRQ_Handler(void)
|
||||
{
|
||||
PIOS_RTC_irq_handler();
|
||||
}
|
||||
|
||||
#endif /* if defined(PIOS_INCLUDE_RTC) */
|
||||
|
||||
#if defined(PIOS_INCLUDE_SERVO) && defined(PIOS_INCLUDE_TIM)
|
||||
/*
|
||||
* Servo outputs
|
||||
*/
|
||||
#include <pios_servo_priv.h>
|
||||
|
||||
const struct pios_servo_cfg pios_servo_cfg = {
|
||||
.tim_oc_init = {
|
||||
.TIM_OCMode = TIM_OCMode_PWM1,
|
||||
.TIM_OutputState = TIM_OutputState_Enable,
|
||||
.TIM_OutputNState = TIM_OutputNState_Disable,
|
||||
.TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION,
|
||||
.TIM_OCPolarity = TIM_OCPolarity_High,
|
||||
.TIM_OCNPolarity = TIM_OCPolarity_High,
|
||||
.TIM_OCIdleState = TIM_OCIdleState_Reset,
|
||||
.TIM_OCNIdleState = TIM_OCNIdleState_Reset,
|
||||
},
|
||||
.channels = pios_tim_servoport_io1_io2_pins,
|
||||
.num_channels = 8,
|
||||
};
|
||||
|
||||
// const struct pios_servo_cfg pios_servo_rcvr_cfg = {
|
||||
// .tim_oc_init = {
|
||||
// .TIM_OCMode = TIM_OCMode_PWM1,
|
||||
// .TIM_OutputState = TIM_OutputState_Enable,
|
||||
// .TIM_OutputNState = TIM_OutputNState_Disable,
|
||||
// .TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION,
|
||||
// .TIM_OCPolarity = TIM_OCPolarity_High,
|
||||
// .TIM_OCNPolarity = TIM_OCPolarity_High,
|
||||
// .TIM_OCIdleState = TIM_OCIdleState_Reset,
|
||||
// .TIM_OCNIdleState = TIM_OCNIdleState_Reset,
|
||||
// },
|
||||
// .channels = pios_tim_servoport_io1_io2_pins,
|
||||
// .num_channels = NELEMENTS(pios_tim_servoport_io1_io2_pins),
|
||||
// };
|
||||
|
||||
#endif /* PIOS_INCLUDE_SERVO && PIOS_INCLUDE_TIM */
|
||||
|
||||
/*
|
||||
* PPM Inputs
|
||||
*/
|
||||
#if defined(PIOS_INCLUDE_PPM)
|
||||
#include <pios_ppm_priv.h>
|
||||
|
||||
const struct pios_ppm_cfg pios_ppm_cfg = {
|
||||
.tim_ic_init = {
|
||||
.TIM_ICPolarity = TIM_ICPolarity_Rising,
|
||||
.TIM_ICSelection = TIM_ICSelection_DirectTI,
|
||||
.TIM_ICPrescaler = TIM_ICPSC_DIV1,
|
||||
.TIM_ICFilter = 0x0,
|
||||
},
|
||||
/* Use only the first channel for ppm */
|
||||
.channels = &pios_tim_servoport_io1_io2_pins[8],
|
||||
.num_channels = 1,
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_PPM */
|
||||
|
||||
/*
|
||||
* PWM Inputs
|
||||
*/
|
||||
#if defined(PIOS_INCLUDE_PWM)
|
||||
#include <pios_pwm_priv.h>
|
||||
|
||||
const struct pios_pwm_cfg pios_pwm_cfg = {
|
||||
.tim_ic_init = {
|
||||
.TIM_ICPolarity = TIM_ICPolarity_Rising,
|
||||
.TIM_ICSelection = TIM_ICSelection_DirectTI,
|
||||
.TIM_ICPrescaler = TIM_ICPSC_DIV1,
|
||||
.TIM_ICFilter = 0x0,
|
||||
},
|
||||
.channels = &pios_tim_servoport_io1_io2_pins[8],
|
||||
.num_channels = 8,
|
||||
};
|
||||
|
||||
#endif /* if defined(PIOS_INCLUDE_PWM) */
|
||||
|
||||
|
||||
/*
|
||||
* SONAR Inputs
|
||||
*/
|
||||
#if defined(PIOS_INCLUDE_HCSR04)
|
||||
#include <pios_hcsr04_priv.h>
|
||||
|
||||
static const struct pios_tim_channel pios_tim_hcsr04_port_all_channels[] = {
|
||||
{
|
||||
.timer = TIM3,
|
||||
.timer_chan = TIM_Channel_2,
|
||||
.pin = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_5,
|
||||
.GPIO_Mode = GPIO_Mode_IPD,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
.remap = GPIO_PartialRemap_TIM3,
|
||||
},
|
||||
};
|
||||
|
||||
const struct pios_hcsr04_cfg pios_hcsr04_cfg = {
|
||||
.tim_ic_init = {
|
||||
.TIM_ICPolarity = TIM_ICPolarity_Rising,
|
||||
.TIM_ICSelection = TIM_ICSelection_DirectTI,
|
||||
.TIM_ICPrescaler = TIM_ICPSC_DIV1,
|
||||
.TIM_ICFilter = 0x0,
|
||||
},
|
||||
.channels = pios_tim_hcsr04_port_all_channels,
|
||||
.num_channels = NELEMENTS(pios_tim_hcsr04_port_all_channels),
|
||||
.trigger = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_6,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
};
|
||||
#endif /* if defined(PIOS_INCLUDE_HCSR04) */
|
||||
|
||||
#if defined(PIOS_INCLUDE_I2C)
|
||||
|
||||
#include <pios_i2c_priv.h>
|
||||
|
||||
/*
|
||||
* I2C Adapters
|
||||
*/
|
||||
|
||||
void PIOS_I2C_ev_irq_handler(void);
|
||||
void PIOS_I2C_er_irq_handler(void);
|
||||
void I2C1_EV_EXTI23_IRQHandler() __attribute__((alias("PIOS_I2C_ev_irq_handler")));
|
||||
void I2C1_ER_IRQHandler() __attribute__((alias("PIOS_I2C_er_irq_handler")));
|
||||
|
||||
static const struct pios_i2c_adapter_cfg pios_i2c_cfg = {
|
||||
.regs = I2C1,
|
||||
.remapSCL = GPIO_AF_4,
|
||||
.remapSDA = GPIO_AF_4,
|
||||
.init = {
|
||||
.I2C_Mode = I2C_Mode_I2C,
|
||||
.I2C_OwnAddress1 = 0,
|
||||
.I2C_Ack = I2C_Ack_Enable,
|
||||
.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit,
|
||||
.I2C_DigitalFilter = 0x00,
|
||||
.I2C_AnalogFilter = I2C_AnalogFilter_Enable,
|
||||
// .I2C_Timing = 0x70310309, // 50kHz I2C @ 8MHz input -> PRESC=0x7, SCLDEL=0x3, SDADEL=0x1, SCLH=0x03, SCLL=0x09
|
||||
.I2C_Timing = 0x00E0257A, // 400 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10.
|
||||
},
|
||||
.transfer_timeout_ms = 50,
|
||||
.scl = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_6,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP,
|
||||
},
|
||||
.pin_source = GPIO_PinSource6,
|
||||
},
|
||||
.sda = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_7,
|
||||
.GPIO_Mode = GPIO_Mode_AF,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_OType = GPIO_OType_PP,
|
||||
.GPIO_PuPd = GPIO_PuPd_UP,
|
||||
},
|
||||
.pin_source = GPIO_PinSource7,
|
||||
},
|
||||
.event = {
|
||||
.flags = 0, /* FIXME: check this */
|
||||
.init = {
|
||||
.NVIC_IRQChannel = I2C1_EV_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.error = {
|
||||
.flags = 0, /* FIXME: check this */
|
||||
.init = {
|
||||
.NVIC_IRQChannel = I2C1_ER_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
uint32_t pios_i2c_id;
|
||||
void PIOS_I2C_ev_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_I2C_EV_IRQ_Handler(pios_i2c_id);
|
||||
}
|
||||
|
||||
void PIOS_I2C_er_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_I2C_ER_IRQ_Handler(pios_i2c_id);
|
||||
}
|
||||
|
||||
|
||||
#endif /* PIOS_INCLUDE_I2C */
|
||||
|
||||
#if defined(PIOS_INCLUDE_GCSRCVR)
|
||||
#include "pios_gcsrcvr_priv.h"
|
||||
#endif /* PIOS_INCLUDE_GCSRCVR */
|
||||
|
||||
#if defined(PIOS_INCLUDE_RCVR)
|
||||
#include "pios_rcvr_priv.h"
|
||||
|
||||
#endif /* PIOS_INCLUDE_RCVR */
|
||||
|
||||
|
||||
#if defined(PIOS_INCLUDE_ADC)
|
||||
#include "pios_adc_priv.h"
|
||||
void PIOS_ADC_DMC_irq_handler(void);
|
||||
void DMA2_Channel1_IRQHandler(void) __attribute__((alias("PIOS_ADC_DMC_irq_handler")));
|
||||
|
||||
struct pios_adc_cfg pios_adc_cfg = {
|
||||
.adc_dev = ADC2,
|
||||
.dma = {
|
||||
.irq = {
|
||||
.flags = (DMA2_FLAG_TC1 | DMA2_FLAG_TE1 | DMA2_FLAG_HT1),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA2_Channel1_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.channel = DMA2_Channel1,
|
||||
}
|
||||
},
|
||||
.half_flag = DMA2_FLAG_HT1,
|
||||
.full_flag = DMA2_FLAG_TC1,
|
||||
};
|
||||
|
||||
void PIOS_ADC_DMC_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_ADC_DMA_Handler();
|
||||
}
|
||||
|
||||
const struct pios_adc_cfg *PIOS_BOARD_HW_DEFS_GetAdcCfg(__attribute__((unused)) uint32_t board_revision)
|
||||
{
|
||||
return &pios_adc_cfg;
|
||||
}
|
||||
#endif /* if defined(PIOS_INCLUDE_ADC) */
|
39
flight/targets/boards/spracingf3/bootloader/Makefile
Normal file
39
flight/targets/boards/spracingf3/bootloader/Makefile
Normal file
@ -0,0 +1,39 @@
|
||||
#
|
||||
# Copyright (c) 2015, The LibrePilot Project, http://www.librepilot.org
|
||||
# Copyright (c) 2009-2013, The OpenPilot Team, http://www.openpilot.org
|
||||
#
|
||||
# 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 FLIGHT_MAKEFILE
|
||||
$(error Top level Makefile must be used to build this target)
|
||||
endif
|
||||
|
||||
PIOS_OMITS_USB = YES
|
||||
PIOS_APPS_MINIMAL = YES
|
||||
|
||||
include ../board-info.mk
|
||||
include $(FLIGHT_ROOT_DIR)/make/firmware-defs.mk
|
||||
|
||||
## The standard CMSIS startup
|
||||
SRC += $(FLIGHTLIB)/ssp.c
|
||||
SRC += $(PIOSCOMMON)/pios_com.c
|
||||
SRC += $(FLIGHTLIB)/fifo_buffer.c
|
||||
|
||||
|
||||
|
||||
include $(FLIGHT_ROOT_DIR)/make/boot-defs.mk
|
||||
include $(FLIGHT_ROOT_DIR)/make/common-defs.mk
|
||||
|
115
flight/targets/boards/spracingf3/bootloader/inc/common.h
Normal file
115
flight/targets/boards/spracingf3/bootloader/inc/common.h
Normal file
@ -0,0 +1,115 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup SPRacingF3 serial BootLoader
|
||||
* @brief These files contain the code to the SPRacingF3 serial Bootloader.
|
||||
*
|
||||
* @{
|
||||
* @file common.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief This file contains various common defines for the BootLoader
|
||||
* @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
|
||||
*/
|
||||
#ifndef COMMON_H_
|
||||
#define COMMON_H_
|
||||
|
||||
// #include "board.h"
|
||||
|
||||
typedef enum {
|
||||
start, keepgoing,
|
||||
} DownloadAction;
|
||||
|
||||
/**************************************************/
|
||||
/* OP_DFU states */
|
||||
/**************************************************/
|
||||
|
||||
typedef enum {
|
||||
DFUidle, // 0
|
||||
uploading, // 1
|
||||
wrong_packet_received, // 2
|
||||
too_many_packets, // 3
|
||||
too_few_packets, // 4
|
||||
Last_operation_Success, // 5
|
||||
downloading, // 6
|
||||
BLidle, // 7
|
||||
Last_operation_failed, // 8
|
||||
uploadingStarting, // 9
|
||||
outsideDevCapabilities, // 10
|
||||
CRC_Fail, // 11
|
||||
failed_jump,
|
||||
// 12
|
||||
} DFUStates;
|
||||
/**************************************************/
|
||||
/* OP_DFU commands */
|
||||
/**************************************************/
|
||||
typedef enum {
|
||||
Reserved, // 0
|
||||
Req_Capabilities, // 1
|
||||
Rep_Capabilities, // 2
|
||||
EnterDFU, // 3
|
||||
JumpFW, // 4
|
||||
Reset, // 5
|
||||
Abort_Operation, // 6
|
||||
Upload, // 7
|
||||
Op_END, // 8
|
||||
Download_Req, // 9
|
||||
Download, // 10
|
||||
Status_Request, // 11
|
||||
Status_Rep
|
||||
// 12
|
||||
} DFUCommands;
|
||||
|
||||
typedef enum {
|
||||
High_Density, Medium_Density
|
||||
} DeviceType;
|
||||
/**************************************************/
|
||||
/* OP_DFU transfer types */
|
||||
/**************************************************/
|
||||
typedef enum {
|
||||
FW, // 0
|
||||
Descript
|
||||
// 2
|
||||
} DFUTransfer;
|
||||
/**************************************************/
|
||||
/* OP_DFU transfer port */
|
||||
/**************************************************/
|
||||
typedef enum {
|
||||
Usb, // 0
|
||||
Serial
|
||||
// 2
|
||||
} DFUPort;
|
||||
/**************************************************/
|
||||
/* OP_DFU programable programable HW types */
|
||||
/**************************************************/
|
||||
typedef enum {
|
||||
Self_flash, // 0
|
||||
Remote_flash_via_spi
|
||||
// 1
|
||||
} DFUProgType;
|
||||
/**************************************************/
|
||||
/* OP_DFU programable sources */
|
||||
/**************************************************/
|
||||
#define USB 0
|
||||
#define SPI 1
|
||||
|
||||
#define DownloadDelay 100000
|
||||
|
||||
#define MAX_DEL_RETRYS 3
|
||||
#define MAX_WRI_RETRYS 3
|
||||
|
||||
#endif /* COMMON_H_ */
|
@ -0,0 +1,52 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup CopterControlBL CopterControl BootLoader
|
||||
* @brief These files contain the code to the CopterControl Bootloader.
|
||||
* @{
|
||||
* @file pios_config.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief PiOS configuration header.
|
||||
* Central compile time config for the project.
|
||||
* In particular, pios_config.h is where you define which PiOS libraries
|
||||
* and features are included in the firmware.
|
||||
* @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
|
||||
*/
|
||||
|
||||
#ifndef PIOS_CONFIG_H
|
||||
#define PIOS_CONFIG_H
|
||||
|
||||
/* Enable/Disable PiOS modules */
|
||||
#define PIOS_INCLUDE_DELAY
|
||||
#define PIOS_INCLUDE_SYS
|
||||
#define PIOS_INCLUDE_IRQ
|
||||
#define PIOS_INCLUDE_GPIO
|
||||
#define PIOS_INCLUDE_LED
|
||||
#define PIOS_INCLUDE_IAP
|
||||
#define PIOS_INCLUDE_COM
|
||||
#define PIOS_INCLUDE_USART
|
||||
#define PIOS_INCLUDE_COM_MSG
|
||||
#define PIOS_INCLUDE_BL_HELPER
|
||||
#define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT
|
||||
|
||||
#endif /* PIOS_CONFIG_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
276
flight/targets/boards/spracingf3/bootloader/main.c
Normal file
276
flight/targets/boards/spracingf3/bootloader/main.c
Normal file
@ -0,0 +1,276 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup SPRacingF3 serial BootLoader
|
||||
* @brief These files contain the code to the SPRacingF3 serial Bootloader.
|
||||
*
|
||||
* @{
|
||||
* @file main.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief This is the file with the main function of the OpenPilot BootLoader
|
||||
* @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>
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <pios_board_info.h>
|
||||
#include <op_dfu.h>
|
||||
#include <pios_iap.h>
|
||||
#include <fifo_buffer.h>
|
||||
#include <pios_com.h>
|
||||
#include <ssp.h>
|
||||
#include <pios_delay.h>
|
||||
#include <pios_board_init.h>
|
||||
#include <pios_board_io.h>
|
||||
|
||||
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 256
|
||||
#define BL_WAIT_TIME 6 * 1000 * 1000
|
||||
#define DFU_BUFFER_SIZE 63
|
||||
|
||||
/* Private macro -------------------------------------------------------------*/
|
||||
/* Private variables ---------------------------------------------------------*/
|
||||
pFunction Jump_To_Application;
|
||||
static uint32_t JumpAddress;
|
||||
|
||||
/// LEDs PWM
|
||||
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 process_buffer[DFU_BUFFER_SIZE];
|
||||
static uint8_t rx_buffer[UART_BUFFER_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 ssp_dfu = false; // signal that ssp data has been received
|
||||
bool User_DFU_request = true;
|
||||
|
||||
|
||||
/* Private function prototypes -----------------------------------------------*/
|
||||
static void led_pwm_step(uint16_t pwm_period, uint16_t pwm_sweep_steps, uint32_t stopwatch, bool default_state);
|
||||
static uint32_t LedPWM(uint16_t pwm_period, uint16_t pwm_sweep_steps, uint32_t count);
|
||||
static void processRX();
|
||||
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 const PortConfig_t ssp_portConfig = {
|
||||
.rxBuf = rxBuf,
|
||||
.rxBufSize = MAX_PACKET_DATA_LEN,
|
||||
.txBuf = txBuf,
|
||||
.txBufSize = MAX_PACKET_DATA_LEN,
|
||||
.max_retry = 1,
|
||||
.timeoutLen = 5000,
|
||||
.pfCallBack = SSP_CallBack,
|
||||
.pfSerialRead = SSP_SerialRead,
|
||||
.pfSerialWrite = SSP_SerialWrite,
|
||||
.pfGetTime = PIOS_DELAY_GetuS,
|
||||
};
|
||||
|
||||
static Port_t ssp_port;
|
||||
static t_fifo_buffer ssp_buffer;
|
||||
|
||||
int main()
|
||||
{
|
||||
PIOS_SYS_Init();
|
||||
PIOS_Board_Init();
|
||||
PIOS_IAP_Init();
|
||||
|
||||
if (PIOS_IAP_CheckRequest() == false) {
|
||||
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);
|
||||
|
||||
uint32_t stopwatch = 0;
|
||||
const uint32_t start_time = PIOS_DELAY_GetuS();
|
||||
while (true) {
|
||||
/* Update the stopwatch */
|
||||
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: // error
|
||||
period1 = 5000;
|
||||
sweep_steps1 = 100;
|
||||
period2 = 5000;
|
||||
sweep_steps2 = 100;
|
||||
}
|
||||
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)
|
||||
{
|
||||
if (pwm_period != 0) {
|
||||
if (LedPWM(pwm_period, pwm_sweep_steps, stopwatch)) {
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT);
|
||||
} else {
|
||||
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
|
||||
}
|
||||
} else {
|
||||
if (default_state) {
|
||||
PIOS_LED_On(PIOS_LED_HEARTBEAT);
|
||||
} else {
|
||||
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
|
||||
}
|
||||
}
|
||||
}
|
||||
void jump_to_app()
|
||||
{
|
||||
const struct pios_board_info *bdinfo = &pios_board_info_blob;
|
||||
|
||||
uint32_t fwIrqStackBase = (*(__IO uint32_t *)bdinfo->fw_base) & 0xFFFE0000;
|
||||
|
||||
// Check for the two possible irqstack locations (sram or core coupled sram)
|
||||
if (fwIrqStackBase == 0x20000000 || fwIrqStackBase == 0x10000000) {
|
||||
FLASH_Lock();
|
||||
RCC_APB2PeriphResetCmd(0xffffffff, ENABLE);
|
||||
RCC_APB1PeriphResetCmd(0xffffffff, ENABLE);
|
||||
RCC_APB2PeriphResetCmd(0xffffffff, DISABLE);
|
||||
RCC_APB1PeriphResetCmd(0xffffffff, DISABLE);
|
||||
|
||||
JumpAddress = *(__IO uint32_t *)(bdinfo->fw_base + 4);
|
||||
Jump_To_Application = (pFunction)JumpAddress;
|
||||
/* Initialize user application's Stack Pointer */
|
||||
__set_MSP(*(__IO uint32_t *)bdinfo->fw_base);
|
||||
Jump_To_Application();
|
||||
} else {
|
||||
DeviceState = failed_jump;
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
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 */
|
||||
|
||||
const uint32_t curr_sweep = (count / (pwm_period * pwm_sweep_steps)); /* ticks once per full sweep */
|
||||
|
||||
if (curr_sweep & 1) {
|
||||
pwm_duty = pwm_period - pwm_duty; /* reverse direction in odd sweeps */
|
||||
}
|
||||
return ((count % pwm_period) > pwm_duty) ? 1 : 0;
|
||||
}
|
||||
uint32_t process_count = 0;
|
||||
void processRX()
|
||||
{
|
||||
do {
|
||||
ssp_ReceiveProcess(&ssp_port);
|
||||
status = ssp_SendProcess(&ssp_port);
|
||||
} 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) {
|
||||
process_buffer[x] = fifoBuf_getByte(&ssp_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);
|
||||
}
|
||||
|
||||
int16_t SSP_SerialRead(void)
|
||||
{
|
||||
uint8_t byte;
|
||||
|
||||
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)
|
||||
{
|
||||
write_cnt++;
|
||||
PIOS_COM_SendChar(PIOS_COM_TELEM_USB, value);
|
||||
}
|
7
flight/targets/boards/spracingf3/bootloader/memory.ld
Normal file
7
flight/targets/boards/spracingf3/bootloader/memory.ld
Normal file
@ -0,0 +1,7 @@
|
||||
MEMORY
|
||||
{
|
||||
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 0x004000 - 0x000080
|
||||
BD_INFO (r) : ORIGIN = 0x08004000 - 0x80, LENGTH = 0x000080
|
||||
SRAM (rwx) : ORIGIN = 0x20000000, LENGTH = 0x009000
|
||||
CCSRAM (rw) : ORIGIN = 0x10000000, LENGTH = 0x002000
|
||||
}
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
x
Reference in New Issue
Block a user