HAL_ChibiOS: added support for MindPX-v2

This commit is contained in:
Andrew Tridgell 2018-01-12 08:25:29 +11:00
parent febe414766
commit 280140bf25
13 changed files with 2530 additions and 3 deletions

View File

@ -44,6 +44,8 @@ static struct gpio_entry {
{1, true, PAL_LINE(GPIOB, 3U)}, // blue
{2, true, PAL_LINE(GPIOB, 11U)}, // red
{3, true, PAL_LINE(GPIOC, 3U)}, // safety
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_MINDPXV2
{0, true, PAL_LINE(GPIOA, 8U)}, // run LED
#endif
};

View File

@ -50,7 +50,7 @@ const struct ChibiRCOutput::pwm_group ChibiRCOutput::pwm_group_list[] =
0,
0
},
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_FMUV3 || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_FMUV4
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_FMUV3 || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_FMUV4 || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_MINDPXV2
&PWMD1
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_SKYVIPER_F412
&PWMD3

View File

@ -88,6 +88,25 @@ extern const AP_HAL::HAL& hal;
#define SPIDEV_ICM 6
#define SPIDEV_RAMTROM 10
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_MINDPXV2
#define SPI_BUS_SENSORS 2
#define SPI_BUS_EXT 1
#define SPI_BUS_RAMTRON 0
#define SPIDEV_CS_GYRO GPIOB, 2
#define SPIDEV_CS_BARO GPIOC, 15
#define SPIDEV_CS_AM GPIOD, 11
#define SPIDEV_CS_MPU GPIOE, 3
#define SPIDEV_CS_RAMTRON GPIOE, 12
#define SPIDEV_CS_RADIO GPIOE, 15
#define SPIDEV_BARO 1
#define SPIDEV_MPU 2
#define SPIDEV_GYRO 3
#define SPIDEV_AM 4
#define SPIDEV_RADIO 5
#define SPIDEV_RAMTROM 6
#endif // CONFIG_HAL_BOARD_SUBTYPE
// SPI mode numbers
@ -101,7 +120,7 @@ extern const AP_HAL::HAL& hal;
#define SPI3_CLOCK STM32_PCLK1
#define SPI4_CLOCK STM32_PCLK2
static struct SPIDriverInfo {
static const struct SPIDriverInfo {
SPIDriver *driver;
uint8_t busid; // used for device IDs in parameters
uint8_t dma_channel_rx;
@ -109,7 +128,7 @@ static struct SPIDriverInfo {
} spi_devices[] = {
{ &SPID1, 1, STM32_SPI_SPI1_RX_DMA_STREAM, STM32_SPI_SPI1_TX_DMA_STREAM },
{ &SPID2, 2, STM32_SPI_SPI2_RX_DMA_STREAM, STM32_SPI_SPI2_TX_DMA_STREAM },
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_FMUV3
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_FMUV3 || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_MINDPXV2
{ &SPID4, 4, STM32_SPI_SPI4_RX_DMA_STREAM, STM32_SPI_SPI4_TX_DMA_STREAM },
#endif
};
@ -144,6 +163,15 @@ SPIDesc SPIDeviceManager::device_table[] = {
SPIDesc("hmc5843", SPI_BUS_SENSORS, SPIDEV_MAG, SPIDEV_CS_MAG, SPIDEV_MODE3, 11*MHZ, 11*MHZ ),
SPIDesc("ramtron", SPI_BUS_RAMTRON, SPIDEV_RAMTROM, SPIDEV_CS_RAMTRON, SPIDEV_MODE3, 8*MHZ, 8*MHZ ),
SPIDesc("lis3mdl", SPI_BUS_SENSORS, SPIDEV_MAG, SPIDEV_CS_MAG, SPIDEV_MODE3, 500*KHZ, 500*KHZ),
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_MINDPXV2
SPIDesc("ms5611", SPI_BUS_SENSORS, SPIDEV_BARO, SPIDEV_CS_BARO, SPIDEV_MODE3, 2*MHZ, 2*MHZ),
SPIDesc("mpu6500", SPI_BUS_SENSORS, SPIDEV_MPU, SPIDEV_CS_MPU, SPIDEV_MODE3,500*KHZ, 2*MHZ),
SPIDesc("lsm9ds0_am", SPI_BUS_SENSORS, SPIDEV_AM, SPIDEV_CS_AM, SPIDEV_MODE3, 11*MHZ, 11*MHZ),
SPIDesc("lsm9ds0_g", SPI_BUS_SENSORS, SPIDEV_GYRO, SPIDEV_CS_GYRO, SPIDEV_MODE3, 11*MHZ, 11*MHZ),
SPIDesc("ramtron", SPI_BUS_RAMTRON, SPIDEV_RAMTROM, SPIDEV_CS_RAMTRON, SPIDEV_MODE3, 8*MHZ, 8*MHZ),
SPIDesc("ramtron0", 0, SPIDEV_RAMTROM, SPIDEV_CS_RAMTRON, SPIDEV_MODE3, 8*MHZ, 8*MHZ),
SPIDesc("ramtron1", 1, SPIDEV_RAMTROM, SPIDEV_CS_RAMTRON, SPIDEV_MODE3, 8*MHZ, 8*MHZ),
SPIDesc("ramtron2", 2, SPIDEV_RAMTROM, SPIDEV_CS_RAMTRON, SPIDEV_MODE3, 8*MHZ, 8*MHZ),
#endif
};

View File

@ -50,6 +50,13 @@ const ChibiUARTDriver::SerialDef ChibiUARTDriver::_serial_tab[] = {
USART1_CONFIG, // Serial 0, debug console
USART6_CONFIG, // Serial 1, GPS
USART2_CONFIG, // Serial 2, sonix
#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_MINDPXV2
{(BaseSequentialStream*) &SDU1, true, false, 0, 0, false, 0, 0},
UART4_CONFIG, // GPS
USART2_CONFIG, // telem1
USART3_CONFIG, // telem2
UART8_CONFIG, // FrSky
USART1_CONFIG, // SBUS
#endif
#if HAL_WITH_IO_MCU
USART6_CONFIG, // IO MCU

View File

@ -0,0 +1,180 @@
/*
* This file 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 file 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, see <http://www.gnu.org/licenses/>.
*
* Modified for use in AP_HAL by Andrew Tridgell and Siddharth Bharat Purohit
*/
#include "hal.h"
#if HAL_USE_PAL || defined(__DOXYGEN__)
/**
* @brief PAL setup.
* @details Digital I/O ports static configuration as defined in @p board.h.
* This variable is used by the HAL when initializing the PAL driver.
*/
const PALConfig pal_default_config = {
{VAL_GPIOA_MODER, VAL_GPIOA_OTYPER, VAL_GPIOA_OSPEEDR, VAL_GPIOA_PUPDR, VAL_GPIOA_ODR, VAL_GPIOA_AFRL, VAL_GPIOA_AFRH},
{VAL_GPIOB_MODER, VAL_GPIOB_OTYPER, VAL_GPIOB_OSPEEDR, VAL_GPIOB_PUPDR, VAL_GPIOB_ODR, VAL_GPIOB_AFRL, VAL_GPIOB_AFRH},
{VAL_GPIOC_MODER, VAL_GPIOC_OTYPER, VAL_GPIOC_OSPEEDR, VAL_GPIOC_PUPDR, VAL_GPIOC_ODR, VAL_GPIOC_AFRL, VAL_GPIOC_AFRH},
{VAL_GPIOD_MODER, VAL_GPIOD_OTYPER, VAL_GPIOD_OSPEEDR, VAL_GPIOD_PUPDR, VAL_GPIOD_ODR, VAL_GPIOD_AFRL, VAL_GPIOD_AFRH},
{VAL_GPIOE_MODER, VAL_GPIOE_OTYPER, VAL_GPIOE_OSPEEDR, VAL_GPIOE_PUPDR, VAL_GPIOE_ODR, VAL_GPIOE_AFRL, VAL_GPIOE_AFRH},
{VAL_GPIOF_MODER, VAL_GPIOF_OTYPER, VAL_GPIOF_OSPEEDR, VAL_GPIOF_PUPDR, VAL_GPIOF_ODR, VAL_GPIOF_AFRL, VAL_GPIOF_AFRH},
{VAL_GPIOG_MODER, VAL_GPIOG_OTYPER, VAL_GPIOG_OSPEEDR, VAL_GPIOG_PUPDR, VAL_GPIOG_ODR, VAL_GPIOG_AFRL, VAL_GPIOG_AFRH},
{VAL_GPIOH_MODER, VAL_GPIOH_OTYPER, VAL_GPIOH_OSPEEDR, VAL_GPIOH_PUPDR, VAL_GPIOH_ODR, VAL_GPIOH_AFRL, VAL_GPIOH_AFRH},
{VAL_GPIOI_MODER, VAL_GPIOI_OTYPER, VAL_GPIOI_OSPEEDR, VAL_GPIOI_PUPDR, VAL_GPIOI_ODR, VAL_GPIOI_AFRL, VAL_GPIOI_AFRH}
};
#endif
/**
* @brief Early initialization code.
* @details This initialization must be performed just after stack setup
* and before any other initialization.
*/
void __early_init(void) {
stm32_clock_init();
}
void __late_init(void) {
halInit();
chSysInit();
#ifdef HAL_USB_PRODUCT_ID
setup_usb_strings();
#endif
}
#if HAL_USE_SDC || defined(__DOXYGEN__)
/**
* @brief SDC card detection.
*/
bool sdc_lld_is_card_inserted(SDCDriver *sdcp) {
static bool last_status = false;
if (blkIsTransferring(sdcp))
return last_status;
return last_status = (bool)palReadPad(GPIOC, 11);
}
/**
* @brief SDC card write protection detection.
*/
bool sdc_lld_is_write_protected(SDCDriver *sdcp) {
(void)sdcp;
return false;
}
#endif /* HAL_USE_SDC */
#if HAL_USE_MMC_SPI || defined(__DOXYGEN__)
/**
* @brief MMC_SPI card detection.
*/
bool mmc_lld_is_card_inserted(MMCDriver *mmcp) {
(void)mmcp;
/* TODO: Fill the implementation.*/
return true;
}
/**
* @brief MMC_SPI card write protection detection.
*/
bool mmc_lld_is_write_protected(MMCDriver *mmcp) {
(void)mmcp;
/* TODO: Fill the implementation.*/
return false;
}
#endif
/**
* @brief Board-specific initialization code.
* @todo Add your board-specific code, if any.
*/
void boardInit(void) {
//Setup ADC pins for Voltage and Current Sensing
palSetPadMode(GPIOA, 2, PAL_MODE_INPUT_ANALOG); //Pin PA2
palSetPadMode(GPIOA, 3, PAL_MODE_INPUT_ANALOG); //Pin PA3
palSetPadMode(GPIOA, 4, PAL_MODE_INPUT_ANALOG); //Pin PA4
palSetPadMode(GPIOE, 12, PAL_STM32_MODE_OUTPUT | PAL_STM32_OTYPE_OPENDRAIN | PAL_STM32_OSPEED_MID2);
palClearPad(GPIOE, 12);
/* External interrupts */
// GPIO_GYRO_DRDY
palSetPadMode(GPIOB, 0, PAL_STM32_MODE_INPUT | PAL_STM32_PUPDR_FLOATING);
// GPIO_MAG_DRDY
palSetPadMode(GPIOB, 1, PAL_STM32_MODE_INPUT | PAL_STM32_PUPDR_FLOATING);
// GPIO_ACCEL_DRDY
palSetPadMode(GPIOB, 4, PAL_STM32_MODE_INPUT | PAL_STM32_PUPDR_FLOATING);
// GPIOI_MPU_DRDY
palSetPadMode(GPIOD, 15, PAL_STM32_MODE_INPUT | PAL_STM32_PUPDR_FLOATING);
/* SPI chip selects */
// // SPIDEV_CS_MS5611
//(GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN7)
palSetPadMode(GPIOD, 7, PAL_STM32_MODE_OUTPUT | PAL_STM32_OTYPE_PUSHPULL | PAL_STM32_OSPEED_LOWEST);
palSetPad(GPIOD, 7);
// GPIO_SPI_CS_FRAM
//(GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10)
palSetPadMode(GPIOD, 10, PAL_STM32_MODE_OUTPUT | PAL_STM32_OTYPE_PUSHPULL | PAL_STM32_OSPEED_LOWEST);
palSetPad(GPIOD, 10);
// SPIDEV_CS_MPU
//(GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN2)
palSetPadMode(GPIOC, 2, PAL_STM32_MODE_OUTPUT | PAL_STM32_OTYPE_PUSHPULL | PAL_STM32_OSPEED_LOWEST);
palSetPad(GPIOC, 2);
// SPIDEV_CS_EXT_MPU
//(GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4)
palSetPadMode(GPIOE, 4, PAL_STM32_MODE_OUTPUT | PAL_STM32_OTYPE_PUSHPULL | PAL_STM32_OSPEED_LOWEST);
palSetPad(GPIOE, 4);
// SPIDEV_CS_EXT_MS5611
//(GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN14)
palSetPadMode(GPIOC, 14, PAL_STM32_MODE_OUTPUT | PAL_STM32_OTYPE_PUSHPULL | PAL_STM32_OSPEED_LOWEST);
palSetPad(GPIOC, 14);
// SPIDEV_CS_EXT_LSM9DS0_AM
//(GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15)
palSetPadMode(GPIOC, 15, PAL_STM32_MODE_OUTPUT | PAL_STM32_OTYPE_PUSHPULL | PAL_STM32_OSPEED_LOWEST);
palSetPad(GPIOC, 15);
// SPIDEV_CS_EXT_LSM9DS0_G
//(GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN13)
palSetPadMode(GPIOC, 13, PAL_STM32_MODE_OUTPUT | PAL_STM32_OTYPE_PUSHPULL | PAL_STM32_OSPEED_LOWEST);
palSetPad(GPIOC, 13);
//PWM O/P Setup
// GPIO_TIM1_CH1OUT
// (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN9)
palSetPadMode(GPIOE, 9, PAL_STM32_MODE_ALTERNATE | PAL_STM32_OTYPE_PUSHPULL | PAL_STM32_OSPEED_MID2 | PAL_STM32_ALTERNATE(1));
palClearPad(GPIOE, 9);
// GPIO_TIM1_CH2OUT
// (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN11)
palSetPadMode(GPIOE, 11, PAL_STM32_MODE_ALTERNATE | PAL_STM32_OTYPE_PUSHPULL | PAL_STM32_OSPEED_MID2 | PAL_STM32_ALTERNATE(1));
palClearPad(GPIOE, 11);
// GPIO_TIM1_CH3OUT
// (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN13)
palSetPadMode(GPIOE, 13, PAL_STM32_MODE_ALTERNATE | PAL_STM32_OTYPE_PUSHPULL | PAL_STM32_OSPEED_MID2 | PAL_STM32_ALTERNATE(1));
palClearPad(GPIOE, 13);
// GPIO_TIM1_CH4OUT
// (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN14)
palSetPadMode(GPIOE, 14, PAL_STM32_MODE_ALTERNATE | PAL_STM32_OTYPE_PUSHPULL | PAL_STM32_OSPEED_MID2 | PAL_STM32_ALTERNATE(1));
palClearPad(GPIOE, 14);
//call extra board specific initialisation method
HAL_BOARD_INIT_HOOK_CALL
}

View File

@ -0,0 +1,47 @@
/*
* This file 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 file 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, see <http://www.gnu.org/licenses/>.
*
* Code by Andrew Tridgell and Siddharth Bharat Purohit
*/
#pragma once
/*
* APM HW Defines
*/
#define PPM_ICU_TIMER ICUD4
#define PPM_ICU_CHANNEL ICU_CHANNEL_2
#define HRT_TIMER GPTD5
#define LINE_LED1 PAL_LINE(GPIOE,12)
#include "hwdef.h"
#ifndef HAL_BOARD_INIT_HOOK_DEFINE
#define HAL_BOARD_INIT_HOOK_DEFINE
#endif
#ifndef HAL_BOARD_INIT_HOOK_CALL
#define HAL_BOARD_INIT_HOOK_CALL
#endif
#if !defined(_FROM_ASM_)
#ifdef __cplusplus
extern "C" {
#endif
void boardInit(void);
HAL_BOARD_INIT_HOOK_DEFINE
#ifdef __cplusplus
}
#endif
#endif /* _FROM_ASM_ */

View File

@ -0,0 +1,519 @@
/*
* This file 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 file 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, see <http://www.gnu.org/licenses/>.
*
* Modified for use in AP_HAL by Andrew Tridgell and Siddharth Bharat Purohit
*/
/**
* @file templates/chconf.h
* @brief Configuration file template.
* @details A copy of this file must be placed in each project directory, it
* contains the application specific kernel settings.
*
* @addtogroup config
* @details Kernel related settings and hooks.
* @{
*/
#pragma once
#define _CHIBIOS_RT_CONF_
/*===========================================================================*/
/**
* @name System timers settings
* @{
*/
/*===========================================================================*/
/**
* @brief System time counter resolution.
* @note Allowed values are 16 or 32 bits.
*/
#define CH_CFG_ST_RESOLUTION 32
/**
* @brief System tick frequency.
* @details Frequency of the system timer that drives the system ticks. This
* setting also defines the system tick time unit.
*/
#define CH_CFG_ST_FREQUENCY 10000
/**
* @brief Time delta constant for the tick-less mode.
* @note If this value is zero then the system uses the classic
* periodic tick. This value represents the minimum number
* of ticks that is safe to specify in a timeout directive.
* The value one is not valid, timeouts are rounded up to
* this value.
*/
#define CH_CFG_ST_TIMEDELTA 2
/** @} */
/*===========================================================================*/
/**
* @name Kernel parameters and options
* @{
*/
/*===========================================================================*/
/**
* @brief Round robin interval.
* @details This constant is the number of system ticks allowed for the
* threads before preemption occurs. Setting this value to zero
* disables the preemption for threads with equal priority and the
* round robin becomes cooperative. Note that higher priority
* threads can still preempt, the kernel is always preemptive.
* @note Disabling the round robin preemption makes the kernel more compact
* and generally faster.
* @note The round robin preemption is not supported in tickless mode and
* must be set to zero in that case.
*/
#define CH_CFG_TIME_QUANTUM 0
/**
* @brief Managed RAM size.
* @details Size of the RAM area to be managed by the OS. If set to zero
* then the whole available RAM is used. The core memory is made
* available to the heap allocator and/or can be used directly through
* the simplified core memory allocator.
*
* @note In order to let the OS manage the whole RAM the linker script must
* provide the @p __heap_base__ and @p __heap_end__ symbols.
* @note Requires @p CH_CFG_USE_MEMCORE.
*/
#define CH_CFG_MEMCORE_SIZE 0
/**
* @brief Idle thread automatic spawn suppression.
* @details When this option is activated the function @p chSysInit()
* does not spawn the idle thread. The application @p main()
* function becomes the idle thread and must implement an
* infinite loop.
*/
#define CH_CFG_NO_IDLE_THREAD FALSE
/** @} */
/*===========================================================================*/
/**
* @name Performance options
* @{
*/
/*===========================================================================*/
/**
* @brief OS optimization.
* @details If enabled then time efficient rather than space efficient code
* is used when two possible implementations exist.
*
* @note This is not related to the compiler optimization options.
* @note The default is @p TRUE.
*/
#define CH_CFG_OPTIMIZE_SPEED TRUE
/** @} */
/*===========================================================================*/
/**
* @name Subsystem options
* @{
*/
/*===========================================================================*/
/**
* @brief Time Measurement APIs.
* @details If enabled then the time measurement APIs are included in
* the kernel.
*
* @note The default is @p TRUE.
*/
#define CH_CFG_USE_TM TRUE
/**
* @brief Threads registry APIs.
* @details If enabled then the registry APIs are included in the kernel.
*
* @note The default is @p TRUE.
*/
#define CH_CFG_USE_REGISTRY TRUE
/**
* @brief Threads synchronization APIs.
* @details If enabled then the @p chThdWait() function is included in
* the kernel.
*
* @note The default is @p TRUE.
*/
#define CH_CFG_USE_WAITEXIT TRUE
/**
* @brief Semaphores APIs.
* @details If enabled then the Semaphores APIs are included in the kernel.
*
* @note The default is @p TRUE.
*/
#define CH_CFG_USE_SEMAPHORES TRUE
/**
* @brief Semaphores queuing mode.
* @details If enabled then the threads are enqueued on semaphores by
* priority rather than in FIFO order.
*
* @note The default is @p FALSE. Enable this if you have special
* requirements.
* @note Requires @p CH_CFG_USE_SEMAPHORES.
*/
#define CH_CFG_USE_SEMAPHORES_PRIORITY FALSE
/**
* @brief Mutexes APIs.
* @details If enabled then the mutexes APIs are included in the kernel.
*
* @note The default is @p TRUE.
*/
#define CH_CFG_USE_MUTEXES TRUE
/**
* @brief Enables recursive behavior on mutexes.
* @note Recursive mutexes are heavier and have an increased
* memory footprint.
*
* @note The default is @p FALSE.
* @note Requires @p CH_CFG_USE_MUTEXES.
*/
#define CH_CFG_USE_MUTEXES_RECURSIVE FALSE
/**
* @brief Conditional Variables APIs.
* @details If enabled then the conditional variables APIs are included
* in the kernel.
*
* @note The default is @p TRUE.
* @note Requires @p CH_CFG_USE_MUTEXES.
*/
#define CH_CFG_USE_CONDVARS TRUE
/**
* @brief Conditional Variables APIs with timeout.
* @details If enabled then the conditional variables APIs with timeout
* specification are included in the kernel.
*
* @note The default is @p TRUE.
* @note Requires @p CH_CFG_USE_CONDVARS.
*/
#define CH_CFG_USE_CONDVARS_TIMEOUT TRUE
/**
* @brief Events Flags APIs.
* @details If enabled then the event flags APIs are included in the kernel.
*
* @note The default is @p TRUE.
*/
#define CH_CFG_USE_EVENTS TRUE
/**
* @brief Events Flags APIs with timeout.
* @details If enabled then the events APIs with timeout specification
* are included in the kernel.
*
* @note The default is @p TRUE.
* @note Requires @p CH_CFG_USE_EVENTS.
*/
#define CH_CFG_USE_EVENTS_TIMEOUT TRUE
/**
* @brief Synchronous Messages APIs.
* @details If enabled then the synchronous messages APIs are included
* in the kernel.
*
* @note The default is @p TRUE.
*/
#define CH_CFG_USE_MESSAGES TRUE
/**
* @brief Synchronous Messages queuing mode.
* @details If enabled then messages are served by priority rather than in
* FIFO order.
*
* @note The default is @p FALSE. Enable this if you have special
* requirements.
* @note Requires @p CH_CFG_USE_MESSAGES.
*/
#define CH_CFG_USE_MESSAGES_PRIORITY FALSE
/**
* @brief Mailboxes APIs.
* @details If enabled then the asynchronous messages (mailboxes) APIs are
* included in the kernel.
*
* @note The default is @p TRUE.
* @note Requires @p CH_CFG_USE_SEMAPHORES.
*/
#define CH_CFG_USE_MAILBOXES TRUE
/**
* @brief Core Memory Manager APIs.
* @details If enabled then the core memory manager APIs are included
* in the kernel.
*
* @note The default is @p TRUE.
*/
#define CH_CFG_USE_MEMCORE TRUE
/**
* @brief Heap Allocator APIs.
* @details If enabled then the memory heap allocator APIs are included
* in the kernel.
*
* @note The default is @p TRUE.
* @note Requires @p CH_CFG_USE_MEMCORE and either @p CH_CFG_USE_MUTEXES or
* @p CH_CFG_USE_SEMAPHORES.
* @note Mutexes are recommended.
*/
#define CH_CFG_USE_HEAP TRUE
/**
* @brief Memory Pools Allocator APIs.
* @details If enabled then the memory pools allocator APIs are included
* in the kernel.
*
* @note The default is @p TRUE.
*/
#define CH_CFG_USE_MEMPOOLS TRUE
/**
* @brief Dynamic Threads APIs.
* @details If enabled then the dynamic threads creation APIs are included
* in the kernel.
*
* @note The default is @p TRUE.
* @note Requires @p CH_CFG_USE_WAITEXIT.
* @note Requires @p CH_CFG_USE_HEAP and/or @p CH_CFG_USE_MEMPOOLS.
*/
#define CH_CFG_USE_DYNAMIC TRUE
/** @} */
/*===========================================================================*/
/**
* @name Debug options
* @{
*/
/*===========================================================================*/
/**
* @brief Debug option, kernel statistics.
*
* @note The default is @p FALSE.
*/
#define CH_DBG_STATISTICS TRUE
/**
* @brief Debug option, system state check.
* @details If enabled the correct call protocol for system APIs is checked
* at runtime.
*
* @note The default is @p FALSE.
*/
#define CH_DBG_SYSTEM_STATE_CHECK TRUE
/**
* @brief Debug option, parameters checks.
* @details If enabled then the checks on the API functions input
* parameters are activated.
*
* @note The default is @p FALSE.
*/
#define CH_DBG_ENABLE_CHECKS TRUE
/**
* @brief Debug option, consistency checks.
* @details If enabled then all the assertions in the kernel code are
* activated. This includes consistency checks inside the kernel,
* runtime anomalies and port-defined checks.
*
* @note The default is @p FALSE.
*/
#define CH_DBG_ENABLE_ASSERTS TRUE
/**
* @brief Debug option, trace buffer.
* @details If enabled then the trace buffer is activated.
*
* @note The default is @p CH_DBG_TRACE_MASK_DISABLED.
*/
#define CH_DBG_TRACE_MASK CH_DBG_TRACE_MASK_NONE
/**
* @brief Trace buffer entries.
* @note The trace buffer is only allocated if @p CH_DBG_TRACE_MASK is
* different from @p CH_DBG_TRACE_MASK_DISABLED.
*/
#define CH_DBG_TRACE_BUFFER_SIZE 128
/**
* @brief Debug option, stack checks.
* @details If enabled then a runtime stack check is performed.
*
* @note The default is @p FALSE.
* @note The stack check is performed in a architecture/port dependent way.
* It may not be implemented or some ports.
* @note The default failure mode is to halt the system with the global
* @p panic_msg variable set to @p NULL.
*/
#define CH_DBG_ENABLE_STACK_CHECK TRUE
/**
* @brief Debug option, stacks initialization.
* @details If enabled then the threads working area is filled with a byte
* value when a thread is created. This can be useful for the
* runtime measurement of the used stack.
*
* @note The default is @p FALSE.
*/
#define CH_DBG_FILL_THREADS TRUE
/**
* @brief Debug option, threads profiling.
* @details If enabled then a field is added to the @p thread_t structure that
* counts the system ticks occurred while executing the thread.
*
* @note The default is @p FALSE.
* @note This debug option is not currently compatible with the
* tickless mode.
*/
#define CH_DBG_THREADS_PROFILING FALSE
/** @} */
/*===========================================================================*/
/**
* @name Kernel hooks
* @{
*/
/*===========================================================================*/
/**
* @brief Threads descriptor structure extension.
* @details User fields added to the end of the @p thread_t structure.
*/
#define CH_CFG_THREAD_EXTRA_FIELDS \
/* Add threads custom fields here.*/
/**
* @brief Threads initialization hook.
* @details User initialization code added to the @p chThdInit() API.
*
* @note It is invoked from within @p chThdInit() and implicitly from all
* the threads creation APIs.
*/
#define CH_CFG_THREAD_INIT_HOOK(tp) { \
/* Add threads initialization code here.*/ \
}
/**
* @brief Threads finalization hook.
* @details User finalization code added to the @p chThdExit() API.
*/
#define CH_CFG_THREAD_EXIT_HOOK(tp) { \
/* Add threads finalization code here.*/ \
}
/**
* @brief Context switch hook.
* @details This hook is invoked just before switching between threads.
*/
#define CH_CFG_CONTEXT_SWITCH_HOOK(ntp, otp) { \
/* Context switch code here.*/ \
}
/**
* @brief ISR enter hook.
*/
#define CH_CFG_IRQ_PROLOGUE_HOOK() { \
/* IRQ prologue code here.*/ \
}
/**
* @brief ISR exit hook.
*/
#define CH_CFG_IRQ_EPILOGUE_HOOK() { \
/* IRQ epilogue code here.*/ \
}
/**
* @brief Idle thread enter hook.
* @note This hook is invoked within a critical zone, no OS functions
* should be invoked from here.
* @note This macro can be used to activate a power saving mode.
*/
#define CH_CFG_IDLE_ENTER_HOOK() { \
/* Idle-enter code here.*/ \
}
/**
* @brief Idle thread leave hook.
* @note This hook is invoked within a critical zone, no OS functions
* should be invoked from here.
* @note This macro can be used to deactivate a power saving mode.
*/
#define CH_CFG_IDLE_LEAVE_HOOK() { \
/* Idle-leave code here.*/ \
}
/**
* @brief Idle Loop hook.
* @details This hook is continuously invoked by the idle thread loop.
*/
#define CH_CFG_IDLE_LOOP_HOOK() { \
/* Idle loop code here.*/ \
}
/**
* @brief System tick event hook.
* @details This hook is invoked in the system tick handler immediately
* after processing the virtual timers queue.
*/
#define CH_CFG_SYSTEM_TICK_HOOK() { \
/* System tick event code here.*/ \
}
/**
* @brief System halt hook.
* @details This hook is invoked in case to a system halting error before
* the system is halted.
*/
#define CH_CFG_SYSTEM_HALT_HOOK(reason) { \
/* System halt code here.*/ \
}
/**
* @brief Trace hook.
* @details This hook is invoked each time a new record is written in the
* trace buffer.
*/
#define CH_CFG_TRACE_HOOK(tep) { \
/* Trace code here.*/ \
}
/** @} */
/*===========================================================================*/
/* Port-specific settings (override port settings defaulted in chcore.h). */
/*===========================================================================*/
/** @} */

View File

@ -0,0 +1,228 @@
##############################################################################
# Build global options
# NOTE: Can be overridden externally.
#
# Compiler options here.
ifeq ($(USE_OPT),)
USE_OPT = -Os -g -fomit-frame-pointer -falign-functions=16 -DCHPRINTF_USE_FLOAT=1
endif
# C specific options here (added to USE_OPT).
ifeq ($(USE_COPT),)
USE_COPT =
endif
# C++ specific options here (added to USE_OPT).
ifeq ($(USE_CPPOPT),)
USE_CPPOPT = -fno-rtti
endif
# Enable this if you want the linker to remove unused code and data
ifeq ($(USE_LINK_GC),)
USE_LINK_GC = yes
endif
# Linker extra options here.
ifeq ($(USE_LDOPT),)
USE_LDOPT =
endif
# Enable this if you want link time optimizations (LTO)
ifeq ($(USE_LTO),)
USE_LTO = no
endif
# If enabled, this option allows to compile the application in THUMB mode.
ifeq ($(USE_THUMB),)
USE_THUMB = yes
endif
# Enable this if you want to see the full log while compiling.
ifeq ($(USE_VERBOSE_COMPILE),)
USE_VERBOSE_COMPILE = no
endif
# If enabled, this option makes the build process faster by not compiling
# modules not used in the current configuration.
ifeq ($(USE_SMART_BUILD),)
USE_SMART_BUILD = no
endif
#
# Build global options
##############################################################################
##############################################################################
# Architecture or project specific options
#
HWDEF = $(AP_HAL)/hwdef
# Stack size to be allocated to the Cortex-M process stack. This stack is
# the stack used by the main() thread.
ifeq ($(USE_PROCESS_STACKSIZE),)
USE_PROCESS_STACKSIZE = 0x400
endif
# Stack size to the allocated to the Cortex-M main/exceptions stack. This
# stack is used for processing interrupts and exceptions.
ifeq ($(USE_EXCEPTIONS_STACKSIZE),)
USE_EXCEPTIONS_STACKSIZE = 0x400
endif
# Enables the use of FPU (no, softfp, hard).
ifeq ($(USE_FPU),)
USE_FPU = hard
endif
#
# Architecture or project specific options
##############################################################################
##############################################################################
# Project, sources and paths
#
# Define project name here
PROJECT = ch
# Imported source files and paths
# Startup files.
include $(CHIBIOS)/os/common/startup/ARMCMx/compilers/GCC/mk/startup_stm32f4xx.mk
# HAL-OSAL files (optional).
include $(CHIBIOS)/os/hal/hal.mk
include $(CHIBIOS)/os/hal/ports/STM32/STM32F4xx/platform.mk
include $(CHIBIOS)/os/hal/osal/rt/osal.mk
# RTOS files (optional).
include $(CHIBIOS)/os/rt/rt.mk
include $(CHIBIOS)/os/common/ports/ARMCMx/compilers/GCC/mk/port_v7m.mk
# Other files (optional).
#include $(CHIBIOS)/test/rt/test.mk
include $(CHIBIOS)/os/hal/lib/streams/streams.mk
include $(CHIBIOS)/os/various/fatfs_bindings/fatfs.mk
VARIOUSSRC = $(STREAMSSRC)
VARIOUSINC = $(STREAMSINC)
# C sources that can be compiled in ARM or THUMB mode depending on the global
# setting.
CSRC = $(STARTUPSRC) \
$(KERNSRC) \
$(PORTSRC) \
$(OSALSRC) \
$(HALSRC) \
$(PLATFORMSRC) \
$(VARIOUSSRC) \
$(FATFSSRC) \
$(HWDEF)/common/stubs.c \
$(HWDEF)/mindpx-v2/board.c \
$(HWDEF)/common/usbcfg.c \
$(HWDEF)/common/ppm.c \
$(HWDEF)/common/flash.c \
$(HWDEF)/common/malloc.c \
$(HWDEF)/common/stdio.c \
$(HWDEF)/common/posix.c \
$(HWDEF)/common/hrt.c
# $(TESTSRC) \
# test.c
# C++ sources that can be compiled in ARM or THUMB mode depending on the global
# setting.
CPPSRC =
# C sources to be compiled in ARM mode regardless of the global setting.
# NOTE: Mixing ARM and THUMB mode enables the -mthumb-interwork compiler
# option that results in lower performance and larger code size.
ACSRC =
# C++ sources to be compiled in ARM mode regardless of the global setting.
# NOTE: Mixing ARM and THUMB mode enables the -mthumb-interwork compiler
# option that results in lower performance and larger code size.
ACPPSRC =
# C sources to be compiled in THUMB mode regardless of the global setting.
# NOTE: Mixing ARM and THUMB mode enables the -mthumb-interwork compiler
# option that results in lower performance and larger code size.
TCSRC =
# C sources to be compiled in THUMB mode regardless of the global setting.
# NOTE: Mixing ARM and THUMB mode enables the -mthumb-interwork compiler
# option that results in lower performance and larger code size.
TCPPSRC =
# List ASM source files here
ASMSRC =
ASMXSRC = $(STARTUPASM) $(PORTASM) $(OSALASM)
INCDIR = $(CHIBIOS)/os/license \
$(STARTUPINC) $(KERNINC) $(PORTINC) $(OSALINC) $(FATFSINC) \
$(HALINC) $(PLATFORMINC) $(BOARDINC) $(TESTINC) $(VARIOUSINC) \
$(HWDEF)/common $(HWDEF)/mindpx-v2
#
# Project, sources and paths
##############################################################################
##############################################################################
# Compiler settings
#
MCU = cortex-m4
#TRGT = arm-elf-
TRGT = arm-none-eabi-
CC = $(TRGT)gcc
CPPC = $(TRGT)g++
# Enable loading with g++ only if you need C++ runtime support.
# NOTE: You can use C++ even without C++ support if you are careful. C++
# runtime support makes code size explode.
LD = $(TRGT)gcc
#LD = $(TRGT)g++
CP = $(TRGT)objcopy
AS = $(TRGT)gcc -x assembler-with-cpp
AR = $(TRGT)ar
OD = $(TRGT)objdump
SZ = $(TRGT)size
HEX = $(CP) -O ihex
BIN = $(CP) -O binary
# ARM-specific options here
AOPT =
# THUMB-specific options here
TOPT = -mthumb -DTHUMB
# Define C warning options here
CWARN = -Wall -Wextra -Wundef -Wstrict-prototypes
# Define C++ warning options here
CPPWARN = -Wall -Wextra -Wundef
#
# Compiler settings
##############################################################################
##############################################################################
# Start of user section
#
# List all user C define here, like -D_DEBUG=1
UDEFS = -DBOARD_FLASH_SIZE=2048
# Define ASM defines here
UADEFS =
# List all user directories here
UINCDIR =
# List the user directory to look for the libraries here
ULIBDIR =
# List all user libraries here
ULIBS =
#
# End of user defines
##############################################################################
include $(HWDEF)/common/chibios_common.mk

View File

@ -0,0 +1,272 @@
#pragma once
/* CHIBIOS FIX */
#include "ch.h"
/*---------------------------------------------------------------------------/
/ FatFs - FAT file system module configuration file
/---------------------------------------------------------------------------*/
#define _FFCONF 68020 /* Revision ID */
/*---------------------------------------------------------------------------/
/ Function Configurations
/---------------------------------------------------------------------------*/
#define _FS_READONLY 0
/* This option switches read-only configuration. (0:Read/Write or 1:Read-only)
/ Read-only configuration removes writing API functions, f_write(), f_sync(),
/ f_unlink(), f_mkdir(), f_chmod(), f_rename(), f_truncate(), f_getfree()
/ and optional writing functions as well. */
#define _FS_MINIMIZE 0
/* This option defines minimization level to remove some basic API functions.
/
/ 0: All basic functions are enabled.
/ 1: f_stat(), f_getfree(), f_unlink(), f_mkdir(), f_truncate() and f_rename()
/ are removed.
/ 2: f_opendir(), f_readdir() and f_closedir() are removed in addition to 1.
/ 3: f_lseek() function is removed in addition to 2. */
#define _USE_STRFUNC 0
/* This option switches string functions, f_gets(), f_putc(), f_puts() and
/ f_printf().
/
/ 0: Disable string functions.
/ 1: Enable without LF-CRLF conversion.
/ 2: Enable with LF-CRLF conversion. */
#define _USE_FIND 0
/* This option switches filtered directory read functions, f_findfirst() and
/ f_findnext(). (0:Disable, 1:Enable 2:Enable with matching altname[] too) */
#define _USE_MKFS 0
/* This option switches f_mkfs() function. (0:Disable or 1:Enable) */
#define _USE_FASTSEEK 0
/* This option switches fast seek function. (0:Disable or 1:Enable) */
#define _USE_EXPAND 0
/* This option switches f_expand function. (0:Disable or 1:Enable) */
#define _USE_CHMOD 1
/* This option switches attribute manipulation functions, f_chmod() and f_utime().
/ (0:Disable or 1:Enable) Also _FS_READONLY needs to be 0 to enable this option. */
#define _USE_LABEL 0
/* This option switches volume label functions, f_getlabel() and f_setlabel().
/ (0:Disable or 1:Enable) */
#define _USE_FORWARD 0
/* This option switches f_forward() function. (0:Disable or 1:Enable) */
/*---------------------------------------------------------------------------/
/ Locale and Namespace Configurations
/---------------------------------------------------------------------------*/
#define _CODE_PAGE 850
/* This option specifies the OEM code page to be used on the target system.
/ Incorrect setting of the code page can cause a file open failure.
/
/ 1 - ASCII (No extended character. Non-LFN cfg. only)
/ 437 - U.S.
/ 720 - Arabic
/ 737 - Greek
/ 771 - KBL
/ 775 - Baltic
/ 850 - Latin 1
/ 852 - Latin 2
/ 855 - Cyrillic
/ 857 - Turkish
/ 860 - Portuguese
/ 861 - Icelandic
/ 862 - Hebrew
/ 863 - Canadian French
/ 864 - Arabic
/ 865 - Nordic
/ 866 - Russian
/ 869 - Greek 2
/ 932 - Japanese (DBCS)
/ 936 - Simplified Chinese (DBCS)
/ 949 - Korean (DBCS)
/ 950 - Traditional Chinese (DBCS)
*/
#define _USE_LFN 3
#define _MAX_LFN 255
/* The _USE_LFN switches the support of long file name (LFN).
/
/ 0: Disable support of LFN. _MAX_LFN has no effect.
/ 1: Enable LFN with static working buffer on the BSS. Always NOT thread-safe.
/ 2: Enable LFN with dynamic working buffer on the STACK.
/ 3: Enable LFN with dynamic working buffer on the HEAP.
/
/ To enable the LFN, Unicode handling functions (option/unicode.c) must be added
/ to the project. The working buffer occupies (_MAX_LFN + 1) * 2 bytes and
/ additional 608 bytes at exFAT enabled. _MAX_LFN can be in range from 12 to 255.
/ It should be set 255 to support full featured LFN operations.
/ When use stack for the working buffer, take care on stack overflow. When use heap
/ memory for the working buffer, memory management functions, ff_memalloc() and
/ ff_memfree(), must be added to the project. */
#define _LFN_UNICODE 0
/* This option switches character encoding on the API. (0:ANSI/OEM or 1:UTF-16)
/ To use Unicode string for the path name, enable LFN and set _LFN_UNICODE = 1.
/ This option also affects behavior of string I/O functions. */
#define _STRF_ENCODE 3
/* When _LFN_UNICODE == 1, this option selects the character encoding ON THE FILE to
/ be read/written via string I/O functions, f_gets(), f_putc(), f_puts and f_printf().
/
/ 0: ANSI/OEM
/ 1: UTF-16LE
/ 2: UTF-16BE
/ 3: UTF-8
/
/ This option has no effect when _LFN_UNICODE == 0. */
#define _FS_RPATH 1
/* This option configures support of relative path.
/
/ 0: Disable relative path and remove related functions.
/ 1: Enable relative path. f_chdir() and f_chdrive() are available.
/ 2: f_getcwd() function is available in addition to 1.
*/
/*---------------------------------------------------------------------------/
/ Drive/Volume Configurations
/---------------------------------------------------------------------------*/
#define _VOLUMES 1
/* Number of volumes (logical drives) to be used. */
#define _STR_VOLUME_ID 0
#define _VOLUME_STRS "RAM","NAND","CF","SD","SD2","USB","USB2","USB3"
/* _STR_VOLUME_ID switches string support of volume ID.
/ When _STR_VOLUME_ID is set to 1, also pre-defined strings can be used as drive
/ number in the path name. _VOLUME_STRS defines the drive ID strings for each
/ logical drives. Number of items must be equal to _VOLUMES. Valid characters for
/ the drive ID strings are: A-Z and 0-9. */
#define _MULTI_PARTITION 0
/* This option switches support of multi-partition on a physical drive.
/ By default (0), each logical drive number is bound to the same physical drive
/ number and only an FAT volume found on the physical drive will be mounted.
/ When multi-partition is enabled (1), each logical drive number can be bound to
/ arbitrary physical drive and partition listed in the VolToPart[]. Also f_fdisk()
/ funciton will be available. */
#define _MIN_SS 512
#define _MAX_SS 512
/* These options configure the range of sector size to be supported. (512, 1024,
/ 2048 or 4096) Always set both 512 for most systems, all type of memory cards and
/ harddisk. But a larger value may be required for on-board flash memory and some
/ type of optical media. When _MAX_SS is larger than _MIN_SS, FatFs is configured
/ to variable sector size and GET_SECTOR_SIZE command must be implemented to the
/ disk_ioctl() function. */
#define _USE_TRIM 0
/* This option switches support of ATA-TRIM. (0:Disable or 1:Enable)
/ To enable Trim function, also CTRL_TRIM command should be implemented to the
/ disk_ioctl() function. */
#define _FS_NOFSINFO 0
/* If you need to know correct free space on the FAT32 volume, set bit 0 of this
/ option, and f_getfree() function at first time after volume mount will force
/ a full FAT scan. Bit 1 controls the use of last allocated cluster number.
/
/ bit0=0: Use free cluster count in the FSINFO if available.
/ bit0=1: Do not trust free cluster count in the FSINFO.
/ bit1=0: Use last allocated cluster number in the FSINFO if available.
/ bit1=1: Do not trust last allocated cluster number in the FSINFO.
*/
/*---------------------------------------------------------------------------/
/ System Configurations
/---------------------------------------------------------------------------*/
#define _FS_TINY 0
/* This option switches tiny buffer configuration. (0:Normal or 1:Tiny)
/ At the tiny configuration, size of file object (FIL) is reduced _MAX_SS bytes.
/ Instead of private sector buffer eliminated from the file object, common sector
/ buffer in the file system object (FATFS) is used for the file data transfer. */
#define _FS_EXFAT 1
/* This option switches support of exFAT file system. (0:Disable or 1:Enable)
/ When enable exFAT, also LFN needs to be enabled. (_USE_LFN >= 1)
/ Note that enabling exFAT discards C89 compatibility. */
#define _FS_NORTC 0
#define _NORTC_MON 1
#define _NORTC_MDAY 1
#define _NORTC_YEAR 2016
/* The option _FS_NORTC switches timestamp functiton. If the system does not have
/ any RTC function or valid timestamp is not needed, set _FS_NORTC = 1 to disable
/ the timestamp function. All objects modified by FatFs will have a fixed timestamp
/ defined by _NORTC_MON, _NORTC_MDAY and _NORTC_YEAR in local time.
/ To enable timestamp function (_FS_NORTC = 0), get_fattime() function need to be
/ added to the project to get current time form real-time clock. _NORTC_MON,
/ _NORTC_MDAY and _NORTC_YEAR have no effect.
/ These options have no effect at read-only configuration (_FS_READONLY = 1). */
#define _FS_LOCK 0
/* The option _FS_LOCK switches file lock function to control duplicated file open
/ and illegal operation to open objects. This option must be 0 when _FS_READONLY
/ is 1.
/
/ 0: Disable file lock function. To avoid volume corruption, application program
/ should avoid illegal open, remove and rename to the open objects.
/ >0: Enable file lock function. The value defines how many files/sub-directories
/ can be opened simultaneously under file lock control. Note that the file
/ lock control is independent of re-entrancy. */
#define _FS_REENTRANT 0
#define _FS_TIMEOUT MS2ST(1000)
#define _SYNC_t semaphore_t*
/* The option _FS_REENTRANT switches the re-entrancy (thread safe) of the FatFs
/ module itself. Note that regardless of this option, file access to different
/ volume is always re-entrant and volume control functions, f_mount(), f_mkfs()
/ and f_fdisk() function, are always not re-entrant. Only file/directory access
/ to the same volume is under control of this function.
/
/ 0: Disable re-entrancy. _FS_TIMEOUT and _SYNC_t have no effect.
/ 1: Enable re-entrancy. Also user provided synchronization handlers,
/ ff_req_grant(), ff_rel_grant(), ff_del_syncobj() and ff_cre_syncobj()
/ function, must be added to the project. Samples are available in
/ option/syscall.c.
/
/ The _FS_TIMEOUT defines timeout period in unit of time tick.
/ The _SYNC_t defines O/S dependent sync object type. e.g. HANDLE, ID, OS_EVENT*,
/ SemaphoreHandle_t and etc.. A header file for O/S definitions needs to be
/ included somewhere in the scope of ff.h. */
/* #include <windows.h> // O/S definitions */
/*--- End of configuration options ---*/

View File

@ -0,0 +1,401 @@
/*
ChibiOS - Copyright (C) 2006..2016 Giovanni Di Sirio
Licensed under the Apache License, Version 2.0 (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.apache.org/licenses/LICENSE-2.0
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.
*/
/*
* This file 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 file 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, see <http://www.gnu.org/licenses/>.
*
* Modified for use in AP_HAL by Andrew Tridgell and Siddharth Bharat Purohit
*/
/**
* @file templates/halconf.h
* @brief HAL configuration header.
* @details HAL configuration file, this file allows to enable or disable the
* various device drivers from your application. You may also use
* this file in order to override the device drivers default settings.
*
* @addtogroup HAL_CONF
* @{
*/
#pragma once
#include "mcuconf.h"
/**
* @brief Enables the PAL subsystem.
*/
#if !defined(HAL_USE_PAL) || defined(__DOXYGEN__)
#define HAL_USE_PAL TRUE
#endif
/**
* @brief Enables the ADC subsystem.
*/
#if !defined(HAL_USE_ADC) || defined(__DOXYGEN__)
#define HAL_USE_ADC TRUE
#endif
/**
* @brief Enables the CAN subsystem.
*/
#if !defined(HAL_USE_CAN) || defined(__DOXYGEN__)
#define HAL_USE_CAN FALSE
#endif
/**
* @brief Enables the DAC subsystem.
*/
#if !defined(HAL_USE_DAC) || defined(__DOXYGEN__)
#define HAL_USE_DAC FALSE
#endif
/**
* @brief Enables the EXT subsystem.
*/
#if !defined(HAL_USE_EXT) || defined(__DOXYGEN__)
#define HAL_USE_EXT TRUE
#endif
/**
* @brief Enables the GPT subsystem.
*/
#if !defined(HAL_USE_GPT) || defined(__DOXYGEN__)
#define HAL_USE_GPT TRUE
#endif
/**
* @brief Enables the I2C subsystem.
*/
#if !defined(HAL_USE_I2C) || defined(__DOXYGEN__)
#define HAL_USE_I2C TRUE
#endif
/**
* @brief Enables the I2S subsystem.
*/
#if !defined(HAL_USE_I2S) || defined(__DOXYGEN__)
#define HAL_USE_I2S FALSE
#endif
/**
* @brief Enables the ICU subsystem.
*/
#if !defined(HAL_USE_ICU) || defined(__DOXYGEN__)
#define HAL_USE_ICU TRUE
#endif
/**
* @brief Enables the MAC subsystem.
*/
#if !defined(HAL_USE_MAC) || defined(__DOXYGEN__)
#define HAL_USE_MAC FALSE
#endif
/**
* @brief Enables the MMC_SPI subsystem.
*/
#if !defined(HAL_USE_MMC_SPI) || defined(__DOXYGEN__)
#define HAL_USE_MMC_SPI FALSE
#endif
/**
* @brief Enables the PWM subsystem.
*/
#if !defined(HAL_USE_PWM) || defined(__DOXYGEN__)
#define HAL_USE_PWM TRUE
#endif
/**
* @brief Enables the QSPI subsystem.
*/
#if !defined(HAL_USE_QSPI) || defined(__DOXYGEN__)
#define HAL_USE_QSPI FALSE
#endif
/**
* @brief Enables the RTC subsystem.
*/
#if !defined(HAL_USE_RTC) || defined(__DOXYGEN__)
#define HAL_USE_RTC FALSE
#endif
/**
* @brief Enables the SDC subsystem.
*/
#if !defined(HAL_USE_SDC) || defined(__DOXYGEN__)
#define HAL_USE_SDC TRUE
#endif
/**
* @brief Enables the SERIAL subsystem.
*/
#if !defined(HAL_USE_SERIAL) || defined(__DOXYGEN__)
#define HAL_USE_SERIAL TRUE
#endif
/**
* @brief Enables the SERIAL over USB subsystem.
*/
#if !defined(HAL_USE_SERIAL_USB) || defined(__DOXYGEN__)
#define HAL_USE_SERIAL_USB TRUE
#endif
/**
* @brief Enables the SPI subsystem.
*/
#if !defined(HAL_USE_SPI) || defined(__DOXYGEN__)
#define HAL_USE_SPI TRUE
#endif
/**
* @brief Enables the UART subsystem.
*/
#if !defined(HAL_USE_UART) || defined(__DOXYGEN__)
#define HAL_USE_UART FALSE
#endif
/**
* @brief Enables the USB subsystem.
*/
#if !defined(HAL_USE_USB) || defined(__DOXYGEN__)
#define HAL_USE_USB TRUE
#endif
/**
* @brief Enables the WDG subsystem.
*/
#if !defined(HAL_USE_WDG) || defined(__DOXYGEN__)
#define HAL_USE_WDG FALSE
#endif
/*===========================================================================*/
/* ADC driver related settings. */
/*===========================================================================*/
/**
* @brief Enables synchronous APIs.
* @note Disabling this option saves both code and data space.
*/
#if !defined(ADC_USE_WAIT) || defined(__DOXYGEN__)
#define ADC_USE_WAIT TRUE
#endif
/**
* @brief Enables the @p adcAcquireBus() and @p adcReleaseBus() APIs.
* @note Disabling this option saves both code and data space.
*/
#if !defined(ADC_USE_MUTUAL_EXCLUSION) || defined(__DOXYGEN__)
#define ADC_USE_MUTUAL_EXCLUSION TRUE
#endif
/*===========================================================================*/
/* CAN driver related settings. */
/*===========================================================================*/
/**
* @brief Sleep mode related APIs inclusion switch.
*/
#if !defined(CAN_USE_SLEEP_MODE) || defined(__DOXYGEN__)
#define CAN_USE_SLEEP_MODE TRUE
#endif
/*===========================================================================*/
/* I2C driver related settings. */
/*===========================================================================*/
/**
* @brief Enables the mutual exclusion APIs on the I2C bus.
*/
#if !defined(I2C_USE_MUTUAL_EXCLUSION) || defined(__DOXYGEN__)
#define I2C_USE_MUTUAL_EXCLUSION TRUE
#endif
/*===========================================================================*/
/* MAC driver related settings. */
/*===========================================================================*/
/**
* @brief Enables an event sources for incoming packets.
*/
#if !defined(MAC_USE_ZERO_COPY) || defined(__DOXYGEN__)
#define MAC_USE_ZERO_COPY FALSE
#endif
/**
* @brief Enables an event sources for incoming packets.
*/
#if !defined(MAC_USE_EVENTS) || defined(__DOXYGEN__)
#define MAC_USE_EVENTS TRUE
#endif
/*===========================================================================*/
/* MMC_SPI driver related settings. */
/*===========================================================================*/
/**
* @brief Delays insertions.
* @details If enabled this options inserts delays into the MMC waiting
* routines releasing some extra CPU time for the threads with
* lower priority, this may slow down the driver a bit however.
* This option is recommended also if the SPI driver does not
* use a DMA channel and heavily loads the CPU.
*/
#if !defined(MMC_NICE_WAITING) || defined(__DOXYGEN__)
#define MMC_NICE_WAITING TRUE
#endif
/*===========================================================================*/
/* SDC driver related settings. */
/*===========================================================================*/
/**
* @brief Number of initialization attempts before rejecting the card.
* @note Attempts are performed at 10mS intervals.
*/
#if !defined(SDC_INIT_RETRY) || defined(__DOXYGEN__)
#define SDC_INIT_RETRY 100
#endif
/**
* @brief Include support for MMC cards.
* @note MMC support is not yet implemented so this option must be kept
* at @p FALSE.
*/
#if !defined(SDC_MMC_SUPPORT) || defined(__DOXYGEN__)
#define SDC_MMC_SUPPORT FALSE
#endif
/**
* @brief Delays insertions.
* @details If enabled this options inserts delays into the MMC waiting
* routines releasing some extra CPU time for the threads with
* lower priority, this may slow down the driver a bit however.
*/
#if !defined(SDC_NICE_WAITING) || defined(__DOXYGEN__)
#define SDC_NICE_WAITING TRUE
#endif
/*===========================================================================*/
/* SERIAL driver related settings. */
/*===========================================================================*/
/**
* @brief Default bit rate.
* @details Configuration parameter, this is the baud rate selected for the
* default configuration.
*/
#if !defined(SERIAL_DEFAULT_BITRATE) || defined(__DOXYGEN__)
#define SERIAL_DEFAULT_BITRATE 38400
#endif
/**
* @brief Serial buffers size.
* @details Configuration parameter, you can change the depth of the queue
* buffers depending on the requirements of your application.
* @note The default is 16 bytes for both the transmission and receive
* buffers.
*/
#if !defined(SERIAL_BUFFERS_SIZE) || defined(__DOXYGEN__)
#define SERIAL_BUFFERS_SIZE 1024
#endif
/*===========================================================================*/
/* SERIAL_USB driver related setting. */
/*===========================================================================*/
/**
* @brief Serial over USB buffers size.
* @details Configuration parameter, the buffer size must be a multiple of
* the USB data endpoint maximum packet size.
* @note The default is 256 bytes for both the transmission and receive
* buffers.
*/
#if !defined(SERIAL_USB_BUFFERS_SIZE) || defined(__DOXYGEN__)
#define SERIAL_USB_BUFFERS_SIZE 256
#endif
/**
* @brief Serial over USB number of buffers.
* @note The default is 2 buffers.
*/
#if !defined(SERIAL_USB_BUFFERS_NUMBER) || defined(__DOXYGEN__)
#define SERIAL_USB_BUFFERS_NUMBER 2
#endif
/*===========================================================================*/
/* SPI driver related settings. */
/*===========================================================================*/
/**
* @brief Enables synchronous APIs.
* @note Disabling this option saves both code and data space.
*/
#if !defined(SPI_USE_WAIT) || defined(__DOXYGEN__)
#define SPI_USE_WAIT TRUE
#endif
/**
* @brief Enables the @p spiAcquireBus() and @p spiReleaseBus() APIs.
* @note Disabling this option saves both code and data space.
*/
#if !defined(SPI_USE_MUTUAL_EXCLUSION) || defined(__DOXYGEN__)
#define SPI_USE_MUTUAL_EXCLUSION TRUE
#endif
/*===========================================================================*/
/* UART driver related settings. */
/*===========================================================================*/
/**
* @brief Enables synchronous APIs.
* @note Disabling this option saves both code and data space.
*/
#if !defined(UART_USE_WAIT) || defined(__DOXYGEN__)
#define UART_USE_WAIT FALSE
#endif
/**
* @brief Enables the @p uartAcquireBus() and @p uartReleaseBus() APIs.
* @note Disabling this option saves both code and data space.
*/
#if !defined(UART_USE_MUTUAL_EXCLUSION) || defined(__DOXYGEN__)
#define UART_USE_MUTUAL_EXCLUSION FALSE
#endif
/*===========================================================================*/
/* USB driver related settings. */
/*===========================================================================*/
/**
* @brief Enables synchronous APIs.
* @note Disabling this option saves both code and data space.
*/
#if !defined(USB_USE_WAIT) || defined(__DOXYGEN__)
#define USB_USE_WAIT FALSE
#endif
/** @} */

View File

@ -0,0 +1,144 @@
# hw definition file for processing by chibios_hwdef.py
# for MindPX-v2 hardware
# MCU class and specific type
MCU STM32F4xx STM32F427xx
# board ID for firmware load
APJ_BOARD_ID 88
# crystal frequency
OSCILLATOR_HZ 8000000
# board voltage
STM32_VDD 330U
# serial port for stdout
STDOUT_SERIAL SD7
STDOUT_BAUDRATE 57600
# USB setup
USB_VENDOR 0x0483 # ST
USB_PRODUCT 0x5740
USB_STRING_MANUFACTURER "ArduPilot"
USB_STRING_PRODUCT "ChibiOS/RT Virtual COM Port"
USB_STRING_SERIAL "100"
I2C_ORDER I2C2 I2C1
# USART7 is debug
# uart
# UART4 is GPS
PA0 UART4_TX UART4
PA1 UART4_RX UART4
PA2 TIM2_CH3 TIM2 # PWM_OUT7
PA3 TIM2_CH4 TIM2 # PWM_OUT8
PA4 VDD_5V_SENS ADC1
# SPI1 is fram bus
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 TONE INPUT
PA8 RUN_LED OUTPUT
PA9 VBUS INPUT
PA10 SBUS_INV OUTPUT
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
PA15 TIM2_CH1 TIM2 # PWM_OUT5
PB0 TIM3_CH3 TIM3 # PWM_OUT3
PB1 TIM3_CH4 TIM3 # PWM_OUT4
PB2 GYRO_CS SPI4 CS
PB3 TIM2_CH2 TIM2 # PWM_OUT6
PB4 TIM3_CH1 TIM3 # PWM_OUT1
PB5 SPI1_MOSI SPI1
# USART1 is SBUS
PB6 USART1_TX USART1
PB7 USART1_RX USART1
# I2C1 is mag I2C
PB8 I2C1_SCL I2C1
PB9 I2C1_SDA I2C1
# I2C2 is FMU I2C
PB10 I2C2_SCL I2C2
PB11 I2C2_SDA I2C2
PB12 FRSKY_INV OUTPUT
# SPI2 is external SPI (radio NRF)
PB13 SPI2_SCK SPI2
PB14 SPI2_MISO SPI2
PB15 SPI2_MOSI SPI2
PC0 BAT_CURR_SENS ADC1
PC1 FMU_GPIO3 INPUT # RSSI
PC2 BAT_VOLT_SENS ADC1
PC3 FMU_ADC1 ADC1
PC4 FMU_ADC2 ADC1
PC5 FMU_ADC3 ADC1
PC6 FMU_GPIO2 INPUT # RCIN
PC7 TIM3_CH2 TIM3 # PWM_OUT2
PC8 SDIO_D0 SDIO
PC9 SDIO_D1 SDIO
PC10 SDIO_D2 SDIO
PC11 SDIO_D3 SDIO
PC12 SDIO_CK SDIO
PC13 ACCEL_DRDY INPUT
PC14 MAG_DRDY INPUT
PC15 BARO_CS SPI4 CS
PD0 CAN1_RX CAN1
PD1 CAN1_TX CAN1
PD2 SDIO_CMD SDIO
# USART2 serial2 telem1
PD3 USART2_CTS USART2
PD4 USART2_RTS USART2
PD5 USART2_TX USART2
PD6 USART2_RX USART2
PD7 NRF_CSN INPUT
# USART3 serial3 telem2
PD8 USART3_TX USART3
PD9 USART3_RX USART3
PD10 NRF_INT INPUT
PD11 ACCEL_MAG_CS SPI4 CS
PD12 TIM4_CH1 TIM4 # FMU_CH5
PD13 TIM4_CH2 TIM4 # FMU_CH6
PD14 TIM4_CH3 TIM4 # FMU_CH7
PD15 TIM4_CH4 TIM4 # FMU_CH8
# UART8 is FrSky
PE0 UART8_RX UART8
PE1 UART8_TX UART8
# SPI4 is M_SPI (main sensors)
PE2 SPI4_SCK SPI4
PE3 MPU_CS SPI4 CS
PE4 GYRO_DRDY INPUT
PE5 SPI4_MISO SPI4
PE6 SPI4_MOSI SPI4
# UART7 is debug
PE7 UART7_RX UART7
PE8 UART7_TX UART7
PE9 TIM1_CH1 TIM1 # FMU_CH1
PE10 MPU_DRDY INPUT
PE11 TIM1_CH2 TIM1 # FMU_CH2
PE12 FRAM_CS SPI1 CS
PE13 TIM1_CH3 TIM1 # FMU_CH3
PE14 TIM1_CH4 TIM1 # FMU_CH4
PE15 NRF_CS SPI2 CS

View File

@ -0,0 +1,393 @@
/*
ChibiOS - Copyright (C) 2006..2015 Giovanni Di Sirio
Licensed under the Apache License, Version 2.0 (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.apache.org/licenses/LICENSE-2.0
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.
*/
/*
* ST32F429xI memory setup.
* Note: Use of ram1, ram2 and ram3 is mutually exclusive with use of ram0.
*/
MEMORY
{
flash : org = 0x08004000, len = 2032K
ram0 : org = 0x20000000, len = 192k /* SRAM1 + SRAM2 + SRAM3 */
ram1 : org = 0x20000000, len = 112k /* SRAM1 */
ram2 : org = 0x2001C000, len = 16k /* SRAM2 */
ram3 : org = 0x20020000, len = 64k /* SRAM3 */
ram4 : org = 0x10000000, len = 64k /* CCM SRAM */
ram5 : org = 0x40024000, len = 4k /* BCKP SRAM */
ram6 : org = 0x00000000, len = 0
ram7 : org = 0x00000000, len = 0
}
/* RAM region to be used for Main stack. This stack accommodates the processing
of all exceptions and interrupts*/
REGION_ALIAS("MAIN_STACK_RAM", ram0);
/* RAM region to be used for the process stack. This is the stack used by
the main() function.*/
REGION_ALIAS("PROCESS_STACK_RAM", ram0);
/* RAM region to be used for data segment.*/
REGION_ALIAS("DATA_RAM", ram0);
/* RAM region to be used for BSS segment.*/
REGION_ALIAS("BSS_RAM", ram0);
/* RAM region to be used for the default heap.*/
REGION_ALIAS("HEAP_RAM", ram0);
__ram0_start__ = ORIGIN(ram0);
__ram0_size__ = LENGTH(ram0);
__ram0_end__ = __ram0_start__ + __ram0_size__;
__ram1_start__ = ORIGIN(ram1);
__ram1_size__ = LENGTH(ram1);
__ram1_end__ = __ram1_start__ + __ram1_size__;
__ram2_start__ = ORIGIN(ram2);
__ram2_size__ = LENGTH(ram2);
__ram2_end__ = __ram2_start__ + __ram2_size__;
__ram3_start__ = ORIGIN(ram3);
__ram3_size__ = LENGTH(ram3);
__ram3_end__ = __ram3_start__ + __ram3_size__;
__ram4_start__ = ORIGIN(ram4);
__ram4_size__ = LENGTH(ram4);
__ram4_end__ = __ram4_start__ + __ram4_size__;
__ram5_start__ = ORIGIN(ram5);
__ram5_size__ = LENGTH(ram5);
__ram5_end__ = __ram5_start__ + __ram5_size__;
__ram6_start__ = ORIGIN(ram6);
__ram6_size__ = LENGTH(ram6);
__ram6_end__ = __ram6_start__ + __ram6_size__;
__ram7_start__ = ORIGIN(ram7);
__ram7_size__ = LENGTH(ram7);
__ram7_end__ = __ram7_start__ + __ram7_size__;
ENTRY(Reset_Handler)
SECTIONS
{
. = 0;
_text = .;
startup : ALIGN(16) SUBALIGN(16)
{
KEEP(*(.vectors))
} > flash
constructors : ALIGN(4) SUBALIGN(4)
{
__init_array_start = .;
KEEP(*(SORT(.init_array.*)))
KEEP(*(.init_array))
__init_array_end = .;
} > flash
destructors : ALIGN(4) SUBALIGN(4)
{
__fini_array_start = .;
KEEP(*(.fini_array))
KEEP(*(SORT(.fini_array.*)))
__fini_array_end = .;
} > flash
.text : ALIGN(16) SUBALIGN(16)
{
*(.text)
*(.text.*)
*(.rodata)
*(.rodata.*)
*(.glue_7t)
*(.glue_7)
*(.gcc*)
} > flash
.ARM.extab :
{
*(.ARM.extab* .gnu.linkonce.armextab.*)
} > flash
.ARM.exidx : {
__exidx_start = .;
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
__exidx_end = .;
} > flash
.eh_frame_hdr :
{
*(.eh_frame_hdr)
} > flash
.eh_frame : ONLY_IF_RO
{
*(.eh_frame)
} > flash
.textalign : ONLY_IF_RO
{
. = ALIGN(8);
} > flash
/* Legacy symbol, not used anywhere.*/
. = ALIGN(4);
PROVIDE(_etext = .);
/* Special section for exceptions stack.*/
.mstack :
{
. = ALIGN(8);
__main_stack_base__ = .;
. += __main_stack_size__;
. = ALIGN(8);
__main_stack_end__ = .;
} > MAIN_STACK_RAM
/* Special section for process stack.*/
.pstack :
{
__process_stack_base__ = .;
__main_thread_stack_base__ = .;
. += __process_stack_size__;
. = ALIGN(8);
__process_stack_end__ = .;
__main_thread_stack_end__ = .;
} > PROCESS_STACK_RAM
.data : ALIGN(4)
{
. = ALIGN(4);
PROVIDE(_textdata = LOADADDR(.data));
PROVIDE(_data = .);
_textdata_start = LOADADDR(.data);
_data_start = .;
*(.data)
*(.data.*)
*(.ramtext)
. = ALIGN(4);
PROVIDE(_edata = .);
_data_end = .;
} > DATA_RAM AT > flash
.bss (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
_bss_start = .;
*(.bss)
*(.bss.*)
*(COMMON)
. = ALIGN(4);
_bss_end = .;
PROVIDE(end = .);
} > BSS_RAM
.ram0_init : ALIGN(4)
{
. = ALIGN(4);
__ram0_init_text__ = LOADADDR(.ram0_init);
__ram0_init__ = .;
*(.ram0_init)
*(.ram0_init.*)
. = ALIGN(4);
} > ram0 AT > flash
.ram0 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram0_clear__ = .;
*(.ram0_clear)
*(.ram0_clear.*)
. = ALIGN(4);
__ram0_noinit__ = .;
*(.ram0)
*(.ram0.*)
. = ALIGN(4);
__ram0_free__ = .;
} > ram0
.ram1_init : ALIGN(4)
{
. = ALIGN(4);
__ram1_init_text__ = LOADADDR(.ram1_init);
__ram1_init__ = .;
*(.ram1_init)
*(.ram1_init.*)
. = ALIGN(4);
} > ram1 AT > flash
.ram1 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram1_clear__ = .;
*(.ram1_clear)
*(.ram1_clear.*)
. = ALIGN(4);
__ram1_noinit__ = .;
*(.ram1)
*(.ram1.*)
. = ALIGN(4);
__ram1_free__ = .;
} > ram1
.ram2_init : ALIGN(4)
{
. = ALIGN(4);
__ram2_init_text__ = LOADADDR(.ram2_init);
__ram2_init__ = .;
*(.ram2_init)
*(.ram2_init.*)
. = ALIGN(4);
} > ram2 AT > flash
.ram2 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram2_clear__ = .;
*(.ram2_clear)
*(.ram2_clear.*)
. = ALIGN(4);
__ram2_noinit__ = .;
*(.ram2)
*(.ram2.*)
. = ALIGN(4);
__ram2_free__ = .;
} > ram2
.ram3_init : ALIGN(4)
{
. = ALIGN(4);
__ram3_init_text__ = LOADADDR(.ram3_init);
__ram3_init__ = .;
*(.ram3_init)
*(.ram3_init.*)
. = ALIGN(4);
} > ram3 AT > flash
.ram3 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram3_clear__ = .;
*(.ram3_clear)
*(.ram3_clear.*)
. = ALIGN(4);
__ram3_noinit__ = .;
*(.ram3)
*(.ram3.*)
. = ALIGN(4);
__ram3_free__ = .;
} > ram3
.ram4_init : ALIGN(4)
{
. = ALIGN(4);
__ram4_init_text__ = LOADADDR(.ram4_init);
__ram4_init__ = .;
*(.ram4_init)
*(.ram4_init.*)
. = ALIGN(4);
} > ram4 AT > flash
.ram4 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram4_clear__ = .;
*(.ram4_clear)
*(.ram4_clear.*)
. = ALIGN(4);
__ram4_noinit__ = .;
*(.ram4)
*(.ram4.*)
. = ALIGN(4);
__ram4_free__ = .;
} > ram4
.ram5_init : ALIGN(4)
{
. = ALIGN(4);
__ram5_init_text__ = LOADADDR(.ram5_init);
__ram5_init__ = .;
*(.ram5_init)
*(.ram5_init.*)
. = ALIGN(4);
} > ram5 AT > flash
.ram5 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram5_clear__ = .;
*(.ram5_clear)
*(.ram5_clear.*)
. = ALIGN(4);
__ram5_noinit__ = .;
*(.ram5)
*(.ram5.*)
. = ALIGN(4);
__ram5_free__ = .;
} > ram5
.ram6_init : ALIGN(4)
{
. = ALIGN(4);
__ram6_init_text__ = LOADADDR(.ram6_init);
__ram6_init__ = .;
*(.ram6_init)
*(.ram6_init.*)
. = ALIGN(4);
} > ram6 AT > flash
.ram6 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram6_clear__ = .;
*(.ram6_clear)
*(.ram6_clear.*)
. = ALIGN(4);
__ram6_noinit__ = .;
*(.ram6)
*(.ram6.*)
. = ALIGN(4);
__ram6_free__ = .;
} > ram6
.ram7_init : ALIGN(4)
{
. = ALIGN(4);
__ram7_init_text__ = LOADADDR(.ram7_init);
__ram7_init__ = .;
*(.ram7_init)
*(.ram7_init.*)
. = ALIGN(4);
} > ram7 AT > flash
.ram7 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram7_clear__ = .;
*(.ram7_clear)
*(.ram7_clear.*)
. = ALIGN(4);
__ram7_noinit__ = .;
*(.ram7)
*(.ram7.*)
. = ALIGN(4);
__ram7_free__ = .;
} > ram7
/* The default heap uses the (statically) unused part of a RAM section.*/
.heap (NOLOAD) :
{
. = ALIGN(8);
__heap_base__ = .;
. = ORIGIN(HEAP_RAM) + LENGTH(HEAP_RAM);
__heap_end__ = .;
} > HEAP_RAM
}

View File

@ -0,0 +1,306 @@
/*
ChibiOS - Copyright (C) 2006..2016 Giovanni Di Sirio
Licensed under the Apache License, Version 2.0 (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.apache.org/licenses/LICENSE-2.0
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.
*/
/*
* This file 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 file 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, see <http://www.gnu.org/licenses/>.
*
* Modified for use in AP_HAL by Andrew Tridgell and Siddharth Bharat Purohit
*/
#pragma once
/*
* STM32F4xx drivers configuration.
* The following settings override the default settings present in
* the various device driver implementation headers.
* Note that the settings for each driver only have effect if the whole
* driver is enabled in halconf.h.
*
* IRQ priorities:
* 15...0 Lowest...Highest.
*
* DMA priorities:
* 0...3 Lowest...Highest.
*/
/*
* HAL driver system settings.
*/
#define STM32_NO_INIT FALSE
#define STM32_HSI_ENABLED TRUE
#define STM32_LSI_ENABLED TRUE
#define STM32_HSE_ENABLED TRUE
#define STM32_LSE_ENABLED FALSE
#define STM32_CLOCK48_REQUIRED TRUE
#define STM32_SW STM32_SW_PLL
#define STM32_PLLSRC STM32_PLLSRC_HSE
#define STM32_PLLM_VALUE 8
#define STM32_PLLN_VALUE 336
#define STM32_PLLP_VALUE 2
#define STM32_PLLQ_VALUE 7
#define STM32_HPRE STM32_HPRE_DIV1
#define STM32_PPRE1 STM32_PPRE1_DIV4
#define STM32_PPRE2 STM32_PPRE2_DIV2
#define STM32_RTCSEL STM32_RTCSEL_LSI
#define STM32_RTCPRE_VALUE 8
#define STM32_MCO1SEL STM32_MCO1SEL_HSI
#define STM32_MCO1PRE STM32_MCO1PRE_DIV1
#define STM32_MCO2SEL STM32_MCO2SEL_SYSCLK
#define STM32_MCO2PRE STM32_MCO2PRE_DIV5
#define STM32_I2SSRC STM32_I2SSRC_CKIN
#define STM32_PLLI2SN_VALUE 192
#define STM32_PLLI2SR_VALUE 5
#define STM32_PVD_ENABLE FALSE
#define STM32_PLS STM32_PLS_LEV0
#define STM32_BKPRAM_ENABLE FALSE
/*
* ADC driver system settings.
*/
#define STM32_ADC_ADCPRE ADC_CCR_ADCPRE_DIV4
#define STM32_ADC_USE_ADC1 TRUE
#define STM32_ADC_USE_ADC2 FALSE
#define STM32_ADC_USE_ADC3 FALSE
#define STM32_ADC_ADC1_DMA_PRIORITY 2
#define STM32_ADC_ADC2_DMA_PRIORITY 2
#define STM32_ADC_ADC3_DMA_PRIORITY 2
#define STM32_ADC_IRQ_PRIORITY 6
#define STM32_ADC_ADC1_DMA_IRQ_PRIORITY 6
#define STM32_ADC_ADC2_DMA_IRQ_PRIORITY 6
#define STM32_ADC_ADC3_DMA_IRQ_PRIORITY 6
/*
* CAN driver system settings.
*/
#define STM32_CAN_USE_CAN1 FALSE
#define STM32_CAN_USE_CAN2 FALSE
#define STM32_CAN_CAN1_IRQ_PRIORITY 11
#define STM32_CAN_CAN2_IRQ_PRIORITY 11
/*
* DAC driver system settings.
*/
#define STM32_DAC_DUAL_MODE FALSE
#define STM32_DAC_USE_DAC1_CH1 FALSE
#define STM32_DAC_USE_DAC1_CH2 FALSE
#define STM32_DAC_DAC1_CH1_IRQ_PRIORITY 10
#define STM32_DAC_DAC1_CH2_IRQ_PRIORITY 10
#define STM32_DAC_DAC1_CH1_DMA_PRIORITY 2
#define STM32_DAC_DAC1_CH2_DMA_PRIORITY 2
/*
* EXT driver system settings.
*/
#define STM32_EXT_EXTI0_IRQ_PRIORITY 6
#define STM32_EXT_EXTI1_IRQ_PRIORITY 6
#define STM32_EXT_EXTI2_IRQ_PRIORITY 6
#define STM32_EXT_EXTI3_IRQ_PRIORITY 6
#define STM32_EXT_EXTI4_IRQ_PRIORITY 6
#define STM32_EXT_EXTI5_9_IRQ_PRIORITY 6
#define STM32_EXT_EXTI10_15_IRQ_PRIORITY 6
#define STM32_EXT_EXTI16_IRQ_PRIORITY 6
#define STM32_EXT_EXTI17_IRQ_PRIORITY 15
#define STM32_EXT_EXTI18_IRQ_PRIORITY 6
#define STM32_EXT_EXTI19_IRQ_PRIORITY 6
#define STM32_EXT_EXTI20_IRQ_PRIORITY 6
#define STM32_EXT_EXTI21_IRQ_PRIORITY 15
#define STM32_EXT_EXTI22_IRQ_PRIORITY 15
/*
* GPT driver system settings.
*/
#define STM32_GPT_USE_TIM1 FALSE
#define STM32_GPT_USE_TIM2 FALSE
#define STM32_GPT_USE_TIM3 FALSE
#define STM32_GPT_USE_TIM4 FALSE
#define STM32_GPT_USE_TIM5 TRUE
#define STM32_GPT_USE_TIM6 FALSE
#define STM32_GPT_USE_TIM7 FALSE
#define STM32_GPT_USE_TIM8 FALSE
#define STM32_GPT_USE_TIM9 FALSE
#define STM32_GPT_USE_TIM11 FALSE
#define STM32_GPT_USE_TIM12 FALSE
#define STM32_GPT_USE_TIM14 FALSE
#define STM32_GPT_TIM1_IRQ_PRIORITY 7
#define STM32_GPT_TIM2_IRQ_PRIORITY 7
#define STM32_GPT_TIM3_IRQ_PRIORITY 7
#define STM32_GPT_TIM4_IRQ_PRIORITY 7
#define STM32_GPT_TIM5_IRQ_PRIORITY 7
#define STM32_GPT_TIM6_IRQ_PRIORITY 7
#define STM32_GPT_TIM7_IRQ_PRIORITY 7
#define STM32_GPT_TIM8_IRQ_PRIORITY 7
#define STM32_GPT_TIM9_IRQ_PRIORITY 7
#define STM32_GPT_TIM11_IRQ_PRIORITY 7
#define STM32_GPT_TIM12_IRQ_PRIORITY 7
#define STM32_GPT_TIM14_IRQ_PRIORITY 7
/*
* I2C driver system settings.
*/
#define STM32_I2C_BUSY_TIMEOUT 50
#define STM32_I2C_I2C1_IRQ_PRIORITY 5
#define STM32_I2C_I2C2_IRQ_PRIORITY 5
#define STM32_I2C_I2C3_IRQ_PRIORITY 5
#define STM32_I2C_I2C1_DMA_PRIORITY 3
#define STM32_I2C_I2C2_DMA_PRIORITY 3
#define STM32_I2C_I2C3_DMA_PRIORITY 3
#define STM32_I2C_DMA_ERROR_HOOK(i2cp) osalSysHalt("DMA failure")
/*
* I2S driver system settings.
*/
#define STM32_I2S_SPI2_IRQ_PRIORITY 10
#define STM32_I2S_SPI3_IRQ_PRIORITY 10
#define STM32_I2S_SPI2_DMA_PRIORITY 1
#define STM32_I2S_SPI3_DMA_PRIORITY 1
#define STM32_I2S_DMA_ERROR_HOOK(i2sp) osalSysHalt("DMA failure")
/*
* ICU driver system settings.
*/
#define STM32_ICU_USE_TIM1 FALSE
#define STM32_ICU_USE_TIM2 FALSE
#define STM32_ICU_USE_TIM3 FALSE
#define STM32_ICU_USE_TIM4 TRUE
#define STM32_ICU_USE_TIM5 FALSE
#define STM32_ICU_USE_TIM8 FALSE
#define STM32_ICU_USE_TIM9 FALSE
#define STM32_ICU_TIM1_IRQ_PRIORITY 7
#define STM32_ICU_TIM2_IRQ_PRIORITY 7
#define STM32_ICU_TIM3_IRQ_PRIORITY 7
#define STM32_ICU_TIM4_IRQ_PRIORITY 7
#define STM32_ICU_TIM5_IRQ_PRIORITY 7
#define STM32_ICU_TIM8_IRQ_PRIORITY 7
#define STM32_ICU_TIM9_IRQ_PRIORITY 7
/*
* MAC driver system settings.
*/
#define STM32_MAC_TRANSMIT_BUFFERS 2
#define STM32_MAC_RECEIVE_BUFFERS 4
#define STM32_MAC_BUFFERS_SIZE 1522
#define STM32_MAC_PHY_TIMEOUT 100
#define STM32_MAC_ETH1_CHANGE_PHY_STATE TRUE
#define STM32_MAC_ETH1_IRQ_PRIORITY 13
#define STM32_MAC_IP_CHECKSUM_OFFLOAD 0
/*
* PWM driver system settings.
*/
#define STM32_PWM_USE_ADVANCED FALSE
#define STM32_PWM_USE_TIM1 TRUE
#define STM32_PWM_USE_TIM2 FALSE
#define STM32_PWM_USE_TIM3 FALSE
#define STM32_PWM_USE_TIM4 FALSE
#define STM32_PWM_USE_TIM5 FALSE
#define STM32_PWM_USE_TIM8 FALSE
#define STM32_PWM_USE_TIM9 FALSE
#define STM32_PWM_TIM1_IRQ_PRIORITY 7
#define STM32_PWM_TIM2_IRQ_PRIORITY 7
#define STM32_PWM_TIM3_IRQ_PRIORITY 7
#define STM32_PWM_TIM4_IRQ_PRIORITY 7
#define STM32_PWM_TIM5_IRQ_PRIORITY 7
#define STM32_PWM_TIM8_IRQ_PRIORITY 7
#define STM32_PWM_TIM9_IRQ_PRIORITY 7
/*
* SDC driver system settings.
*/
#define STM32_SDC_SDIO_DMA_PRIORITY 3
#define STM32_SDC_SDIO_IRQ_PRIORITY 9
#define STM32_SDC_WRITE_TIMEOUT_MS 1000
#define STM32_SDC_READ_TIMEOUT_MS 1000
#define STM32_SDC_CLOCK_ACTIVATION_DELAY 10
#define STM32_SDC_SDIO_UNALIGNED_SUPPORT TRUE
/*
* SERIAL driver system settings.
*/
#define STM32_SERIAL_USART1_PRIORITY 11
#define STM32_SERIAL_USART2_PRIORITY 11
#define STM32_SERIAL_USART3_PRIORITY 11
#define STM32_SERIAL_UART4_PRIORITY 11
#define STM32_SERIAL_UART5_PRIORITY 11
#define STM32_SERIAL_USART6_PRIORITY 11
#define STM32_SERIAL_UART7_PRIORITY 11
#define STM32_SERIAL_UART8_PRIORITY 11
/*
* SPI driver system settings.
*/
#define STM32_SPI_SPI1_DMA_PRIORITY 1
#define STM32_SPI_SPI2_DMA_PRIORITY 1
#define STM32_SPI_SPI3_DMA_PRIORITY 1
#define STM32_SPI_SPI4_DMA_PRIORITY 1
#define STM32_SPI_SPI1_IRQ_PRIORITY 10
#define STM32_SPI_SPI2_IRQ_PRIORITY 10
#define STM32_SPI_SPI3_IRQ_PRIORITY 10
#define STM32_SPI_SPI4_IRQ_PRIORITY 10
#define STM32_SPI_DMA_ERROR_HOOK(spip) osalSysHalt("DMA failure")
/*
* ST driver system settings.
*/
#define STM32_ST_IRQ_PRIORITY 8
#define STM32_ST_USE_TIMER 2
/*
* UART driver system settings.
*/
#define STM32_UART_USART1_IRQ_PRIORITY 12
#define STM32_UART_USART2_IRQ_PRIORITY 12
#define STM32_UART_USART3_IRQ_PRIORITY 12
#define STM32_UART_UART4_IRQ_PRIORITY 12
#define STM32_UART_UART5_IRQ_PRIORITY 12
#define STM32_UART_USART6_IRQ_PRIORITY 12
#define STM32_UART_USART1_DMA_PRIORITY 0
#define STM32_UART_USART2_DMA_PRIORITY 0
#define STM32_UART_USART3_DMA_PRIORITY 0
#define STM32_UART_UART4_DMA_PRIORITY 0
#define STM32_UART_UART5_DMA_PRIORITY 0
#define STM32_UART_USART6_DMA_PRIORITY 0
#define STM32_UART_DMA_ERROR_HOOK(uartp) osalSysHalt("DMA failure")
/*
* USB driver system settings.
*/
#define STM32_USB_USE_OTG1 TRUE
#define STM32_USB_USE_OTG2 FALSE
#define STM32_USB_OTG1_IRQ_PRIORITY 14
#define STM32_USB_OTG2_IRQ_PRIORITY 14
#define STM32_USB_OTG1_RX_FIFO_SIZE 512
#define STM32_USB_OTG2_RX_FIFO_SIZE 1024
#define STM32_USB_OTG_THREAD_PRIO LOWPRIO
#define STM32_USB_OTG_THREAD_STACK_SIZE 128
#define STM32_USB_OTGFIFO_FILL_BASEPRI 0
/*
* WDG driver system settings.
*/
#define STM32_WDG_USE_IWDG FALSE
// include generated config
#include "hwdef.h"