HAL_ChibiOS: use a common makefile and board.c

allow for custom files per board if supplied, but don't require them
for every board
This commit is contained in:
Andrew Tridgell 2018-01-13 08:33:58 +11:00
parent d17e9f321a
commit bae9469af7
13 changed files with 22 additions and 1606 deletions

View File

@ -1,180 +0,0 @@
/*
* 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

@ -1,228 +0,0 @@
##############################################################################
# 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)/fmuv3/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)/fmuv3
#
# 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

@ -13,6 +13,9 @@ OSCILLATOR_HZ 24000000
# board voltage
STM32_VDD 330U
# flash size
FLASH_SIZE_KB 2048
# serial port for stdout
STDOUT_SERIAL SD7
STDOUT_BAUDRATE 57600

View File

@ -1,180 +0,0 @@
/*
* 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

@ -1,228 +0,0 @@
##############################################################################
# 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)/fmuv4/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)/fmuv4
#
# 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

@ -13,6 +13,9 @@ OSCILLATOR_HZ 24000000
# board voltage
STM32_VDD 330U
# flash size
FLASH_SIZE_KB 2048
# serial port for stdout
STDOUT_SERIAL SD7
STDOUT_BAUDRATE 57600

View File

@ -1,180 +0,0 @@
/*
* 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

@ -1,228 +0,0 @@
##############################################################################
# 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

@ -18,6 +18,9 @@ HRT_TIMER 6
# board voltage
STM32_VDD 330U
# flash size
FLASH_SIZE_KB 2048
# serial port for stdout
STDOUT_SERIAL SD7
STDOUT_BAUDRATE 57600

View File

@ -220,7 +220,7 @@ for port in ports:
for pin in range(pincount[port]):
portmap[port].append(generic_pin(port, pin, None, 'INPUT', []))
def get_config(name, column=0, required=True, default=None):
def get_config(name, column=0, required=True, default=None, need_int=False):
'''get a value from config dictionary'''
if not name in config:
if required and default is None:
@ -228,7 +228,12 @@ def get_config(name, column=0, required=True, default=None):
return default
if len(config[name]) < column+1:
error("Error: missing required value %s in hwdef.dat (column %u)" % (name, column))
return config[name][column]
ret = config[name][column]
if need_int:
if not is_int(ret):
error("Config value %s must be an integer (got %s)" % (name, ret))
ret = int(ret)
return ret
def process_line(line):
'''process one line of pin definition file'''
@ -277,7 +282,7 @@ def write_mcu_config(f):
f.write('// UART used for stdout (printf)\n')
f.write('#define HAL_STDOUT_SERIAL %s\n\n' % get_config('STDOUT_SERIAL'))
f.write('// baudrate used for stdout (printf)\n')
f.write('#define HAL_STDOUT_BAUDRATE %s\n\n' % get_config('STDOUT_BAUDRATE'))
f.write('#define HAL_STDOUT_BAUDRATE %u\n\n' % get_config('STDOUT_BAUDRATE', need_int=True))
if 'SDIO' in bytype:
f.write('// SDIO available, enable POSIX filesystem support\n')
f.write('#define USE_POSIX\n\n')
@ -299,6 +304,8 @@ def write_mcu_config(f):
hrt_timer = int(hrt_timer)
f.write('#define HRT_TIMER GPTD%u\n' % hrt_timer)
f.write('#define STM32_GPT_USE_TIM%u TRUE\n' % hrt_timer)
flash_size = get_config('FLASH_SIZE_KB', need_int=True)
f.write('#define BOARD_FLASH_SIZE %u' % flash_size)
f.write('\n')

View File

@ -1,154 +0,0 @@
/*
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
*/
#include "hal.h"
#include "hwdef.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 = {
#if STM32_HAS_GPIOA
{VAL_GPIOA_MODER, VAL_GPIOA_OTYPER, VAL_GPIOA_OSPEEDR, VAL_GPIOA_PUPDR,
VAL_GPIOA_ODR, VAL_GPIOA_AFRL, VAL_GPIOA_AFRH},
#endif
#if STM32_HAS_GPIOB
{VAL_GPIOB_MODER, VAL_GPIOB_OTYPER, VAL_GPIOB_OSPEEDR, VAL_GPIOB_PUPDR,
VAL_GPIOB_ODR, VAL_GPIOB_AFRL, VAL_GPIOB_AFRH},
#endif
#if STM32_HAS_GPIOC
{VAL_GPIOC_MODER, VAL_GPIOC_OTYPER, VAL_GPIOC_OSPEEDR, VAL_GPIOC_PUPDR,
VAL_GPIOC_ODR, VAL_GPIOC_AFRL, VAL_GPIOC_AFRH},
#endif
#if STM32_HAS_GPIOD
{VAL_GPIOD_MODER, VAL_GPIOD_OTYPER, VAL_GPIOD_OSPEEDR, VAL_GPIOD_PUPDR,
VAL_GPIOD_ODR, VAL_GPIOD_AFRL, VAL_GPIOD_AFRH},
#endif
#if STM32_HAS_GPIOE
{VAL_GPIOE_MODER, VAL_GPIOE_OTYPER, VAL_GPIOE_OSPEEDR, VAL_GPIOE_PUPDR,
VAL_GPIOE_ODR, VAL_GPIOE_AFRL, VAL_GPIOE_AFRH},
#endif
#if STM32_HAS_GPIOF
{VAL_GPIOF_MODER, VAL_GPIOF_OTYPER, VAL_GPIOF_OSPEEDR, VAL_GPIOF_PUPDR,
VAL_GPIOF_ODR, VAL_GPIOF_AFRL, VAL_GPIOF_AFRH},
#endif
#if STM32_HAS_GPIOG
{VAL_GPIOG_MODER, VAL_GPIOG_OTYPER, VAL_GPIOG_OSPEEDR, VAL_GPIOG_PUPDR,
VAL_GPIOG_ODR, VAL_GPIOG_AFRL, VAL_GPIOG_AFRH},
#endif
#if STM32_HAS_GPIOH
{VAL_GPIOH_MODER, VAL_GPIOH_OTYPER, VAL_GPIOH_OSPEEDR, VAL_GPIOH_PUPDR,
VAL_GPIOH_ODR, VAL_GPIOH_AFRL, VAL_GPIOH_AFRH},
#endif
#if STM32_HAS_GPIOI
{VAL_GPIOI_MODER, VAL_GPIOI_OTYPER, VAL_GPIOI_OSPEEDR, VAL_GPIOI_PUPDR,
VAL_GPIOI_ODR, VAL_GPIOI_AFRL, VAL_GPIOI_AFRH}
#endif
#if STM32_HAS_GPIOJ
{VAL_GPIOJ_MODER, VAL_GPIOJ_OTYPER, VAL_GPIOJ_OSPEEDR, VAL_GPIOJ_PUPDR,
VAL_GPIOJ_ODR, VAL_GPIOJ_AFRL, VAL_GPIOJ_AFRH},
#endif
#if STM32_HAS_GPIOK
{VAL_GPIOK_MODER, VAL_GPIOK_OTYPER, VAL_GPIOK_OSPEEDR, VAL_GPIOK_PUPDR,
VAL_GPIOK_ODR, VAL_GPIOK_AFRL, VAL_GPIOK_AFRH}
#endif
};
#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();
}
#if HAL_USE_SDC || defined(__DOXYGEN__)
/**
* @brief SDC card detection.
*/
bool sdc_lld_is_card_inserted(SDCDriver *sdcp) {
(void)sdcp;
/* TODO: Fill the implementation.*/
return true;
}
/**
* @brief SDC card write protection detection.
*/
bool sdc_lld_is_write_protected(SDCDriver *sdcp) {
(void)sdcp;
/* TODO: Fill the implementation.*/
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)
{
}

View File

@ -1,225 +0,0 @@
##############################################################################
# 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) \
$(HWDEF)/common/stubs.c \
$(HWDEF)/skyviper-f412/board.c \
$(HWDEF)/common/ppm.c \
$(HWDEF)/common/flash.c \
$(HWDEF)/common/malloc.c \
$(HWDEF)/common/stdio.c \
$(HWDEF)/common/hrt.c
# $(HWDEF)/common/usbcfg.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) \
$(HALINC) $(PLATFORMINC) $(BOARDINC) $(TESTINC) $(VARIOUSINC) \
$(HWDEF)/common $(HWDEF)/skyviper-f412
#
# 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=1024
# 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

@ -23,6 +23,9 @@ STM32_PWM_USE_TIM3 TRUE
# board voltage
STM32_VDD 330U
# flash size
FLASH_SIZE_KB 1024
# serial port for stdout
STDOUT_SERIAL SD1
STDOUT_BAUDRATE 115200