1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-01-18 03:52:11 +01:00

Merge branch 'amorale/OP-1307_discovery_f4_bare' into next

This commit is contained in:
Alessio Morale 2014-05-08 22:56:03 +02:00
commit 16df6bc58c
27 changed files with 5738 additions and 2 deletions

View File

@ -197,7 +197,7 @@ export OPUAVSYNTHDIR := $(BUILD_DIR)/uavobject-synthetics/flight
export OPGCSSYNTHDIR := $(BUILD_DIR)/openpilotgcs-synthetics
# Define supported board lists
ALL_BOARDS := coptercontrol oplinkmini revolution osd revoproto simposix
ALL_BOARDS := coptercontrol oplinkmini revolution osd revoproto simposix discoveryf4bare
# Short names of each board (used to display board name in parallel builds)
coptercontrol_short := 'cc '
@ -206,6 +206,7 @@ revolution_short := 'revo'
osd_short := 'osd '
revoproto_short := 'revp'
simposix_short := 'posx'
discoveryf4bare_short := 'df4b'
# SimPosix only builds on Linux so drop it from the list for
# all other platforms.
@ -697,7 +698,7 @@ endif
##############################
# Firmware files to package
PACKAGE_FW_TARGETS := $(filter-out fw_simposix, $(FW_TARGETS))
PACKAGE_FW_TARGETS := $(filter-out fw_simposix fw_discoveryf4bare, $(FW_TARGETS))
PACKAGE_ELF_TARGETS := $(filter fw_simposix, $(FW_TARGETS))
# Rules to generate GCS resources used to embed firmware binaries into the GCS.

View File

@ -0,0 +1,560 @@
/**
******************************************************************************
* @file system_stm32f4xx.c
* @author MCD Application Team
* @version V1.1.0
* @date 11-January-2013
* @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File.
* This file contains the system clock configuration for STM32F4xx devices,
* and is generated by the clock configuration tool
* stm32f4xx_Clock_Configuration_V1.1.0.xls
*
* 1. This file provides two functions and one global variable to be called from
* user application:
* - SystemInit(): Setups the system clock (System clock source, PLL Multiplier
* and Divider factors, AHB/APBx prescalers and Flash settings),
* depending on the configuration made in the clock xls tool.
* This function is called at startup just after reset and
* before branch to main program. This call is made inside
* the "startup_stm32f4xx.s" file.
*
* - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
* by the user application to setup the SysTick
* timer or configure other parameters.
*
* - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
* be called whenever the core clock is changed
* during program execution.
*
* 2. After each device reset the HSI (16 MHz) is used as system clock source.
* Then SystemInit() function is called, in "startup_stm32f4xx.s" file, to
* configure the system clock before to branch to main program.
*
* 3. If the system clock source selected by user fails to startup, the SystemInit()
* function will do nothing and HSI still used as system clock source. User can
* add some code to deal with this issue inside the SetSysClock() function.
*
* 4. The default value of HSE crystal is set to 25MHz, refer to "HSE_VALUE" define
* in "stm32f4xx.h" file. When HSE is used as system clock source, directly or
* through PLL, and you are using different crystal you have to adapt the HSE
* value to your own configuration.
*
* 5. This file configures the system clock as follows:
*=============================================================================
*=============================================================================
* Supported STM32F40xx/41xx/427x/437x devices
*-----------------------------------------------------------------------------
* System Clock source | PLL (HSE)
*-----------------------------------------------------------------------------
* SYSCLK(Hz) | 168000000
*-----------------------------------------------------------------------------
* HCLK(Hz) | 168000000
*-----------------------------------------------------------------------------
* AHB Prescaler | 1
*-----------------------------------------------------------------------------
* APB1 Prescaler | 4
*-----------------------------------------------------------------------------
* APB2 Prescaler | 2
*-----------------------------------------------------------------------------
* HSE Frequency(Hz) | 8000000
*-----------------------------------------------------------------------------
* PLL_M | 10
*-----------------------------------------------------------------------------
* PLL_N | 420
*-----------------------------------------------------------------------------
* PLL_P | 2
*-----------------------------------------------------------------------------
* PLL_Q | 7
*-----------------------------------------------------------------------------
* PLLI2S_N | NA
*-----------------------------------------------------------------------------
* PLLI2S_R | NA
*-----------------------------------------------------------------------------
* I2S input clock | NA
*-----------------------------------------------------------------------------
* VDD(V) | 3.3
*-----------------------------------------------------------------------------
* Main regulator output voltage | Scale1 mode
*-----------------------------------------------------------------------------
* Flash Latency(WS) | 5
*-----------------------------------------------------------------------------
* Prefetch Buffer | ON
*-----------------------------------------------------------------------------
* Instruction cache | ON
*-----------------------------------------------------------------------------
* Data cache | ON
*-----------------------------------------------------------------------------
* Require 48MHz for USB OTG FS, | Enabled
* SDIO and RNG clock |
*-----------------------------------------------------------------------------
*=============================================================================
******************************************************************************
* @attention
*
* <h2><center>&copy; COPYRIGHT 2013 STMicroelectronics</center></h2>
*
* Licensed under MCD-ST Liberty SW License Agreement V2, (the "License");
* You may not use this file except in compliance with the License.
* You may obtain a copy of the License at:
*
* http://www.st.com/software_license_agreement_liberty_v2
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
******************************************************************************
*/
/** @addtogroup CMSIS
* @{
*/
/** @addtogroup stm32f4xx_system
* @{
*/
/** @addtogroup STM32F4xx_System_Private_Includes
* @{
*/
#include "stm32f4xx.h"
/**
* @}
*/
/** @addtogroup STM32F4xx_System_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F4xx_System_Private_Defines
* @{
*/
/************************* Miscellaneous Configuration ************************/
/*!< Uncomment the following line if you need to use external SRAM mounted
on STM324xG_EVAL/STM324x7I_EVAL boards as data memory */
/* #define DATA_IN_ExtSRAM */
/*!< Uncomment the following line if you need to relocate your vector Table in
Internal SRAM. */
/* #define VECT_TAB_SRAM */
#define VECT_TAB_OFFSET 0x00 /*!< Vector Table base offset field.
This value must be a multiple of 0x200. */
/******************************************************************************/
/************************* PLL Parameters *************************************/
/* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N */
#define PLL_M 10
#define PLL_N 420
/* SYSCLK = PLL_VCO / PLL_P */
#define PLL_P 2
/* USB OTG FS, SDIO and RNG Clock = PLL_VCO / PLLQ */
#define PLL_Q 7
/******************************************************************************/
/**
* @}
*/
/** @addtogroup STM32F4xx_System_Private_Macros
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F4xx_System_Private_Variables
* @{
*/
uint32_t SystemCoreClock = 168000000;
__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
/**
* @}
*/
/** @addtogroup STM32F4xx_System_Private_FunctionPrototypes
* @{
*/
static void SetSysClock(void);
#ifdef DATA_IN_ExtSRAM
static void SystemInit_ExtMemCtl(void);
#endif /* DATA_IN_ExtSRAM */
/**
* @}
*/
/** @addtogroup STM32F4xx_System_Private_Functions
* @{
*/
/**
* @brief Setup the microcontroller system
* Initialize the Embedded Flash Interface, the PLL and update the
* SystemFrequency variable.
* @param None
* @retval None
*/
void SystemInit(void)
{
/* FPU settings ------------------------------------------------------------*/
#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */
#endif
/* Reset the RCC clock configuration to the default reset state ------------*/
/* Set HSION bit */
RCC->CR |= (uint32_t)0x00000001;
/* Reset CFGR register */
RCC->CFGR = 0x00000000;
/* Reset HSEON, CSSON and PLLON bits */
RCC->CR &= (uint32_t)0xFEF6FFFF;
/* Reset PLLCFGR register */
RCC->PLLCFGR = 0x24003010;
/* Reset HSEBYP bit */
RCC->CR &= (uint32_t)0xFFFBFFFF;
/* Disable all interrupts */
RCC->CIR = 0x00000000;
#ifdef DATA_IN_ExtSRAM
SystemInit_ExtMemCtl();
#endif /* DATA_IN_ExtSRAM */
/* Configure the System clock source, PLL Multiplier and Divider factors,
AHB/APBx prescalers and Flash settings ----------------------------------*/
SetSysClock();
/* Configure the Vector Table location add offset address ------------------*/
#ifdef VECT_TAB_SRAM
SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */
#else
SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */
#endif
}
/**
* @brief Update SystemCoreClock variable according to Clock Register Values.
* The SystemCoreClock variable contains the core clock (HCLK), it can
* be used by the user application to setup the SysTick timer or configure
* other parameters.
*
* @note Each time the core clock (HCLK) changes, this function must be called
* to update SystemCoreClock variable value. Otherwise, any configuration
* based on this variable will be incorrect.
*
* @note - The system frequency computed by this function is not the real
* frequency in the chip. It is calculated based on the predefined
* constant and the selected clock source:
*
* - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
*
* - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
*
* - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
* or HSI_VALUE(*) multiplied/divided by the PLL factors.
*
* (*) HSI_VALUE is a constant defined in stm32f4xx.h file (default value
* 16 MHz) but the real value may vary depending on the variations
* in voltage and temperature.
*
* (**) HSE_VALUE is a constant defined in stm32f4xx.h file (default value
* 25 MHz), user has to ensure that HSE_VALUE is same as the real
* frequency of the crystal used. Otherwise, this function may
* have wrong result.
*
* - The result of this function could be not correct when using fractional
* value for HSE crystal.
*
* @param None
* @retval None
*/
void SystemCoreClockUpdate(void)
{
uint32_t tmp = 0, pllvco = 0, pllp = 2, pllsource = 0, pllm = 2;
/* Get SYSCLK source -------------------------------------------------------*/
tmp = RCC->CFGR & RCC_CFGR_SWS;
switch (tmp)
{
case 0x00: /* HSI used as system clock source */
SystemCoreClock = HSI_VALUE;
break;
case 0x04: /* HSE used as system clock source */
SystemCoreClock = HSE_VALUE;
break;
case 0x08: /* PLL used as system clock source */
/* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N
SYSCLK = PLL_VCO / PLL_P
*/
pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22;
pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM;
if (pllsource != 0)
{
/* HSE used as PLL clock source */
pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
}
else
{
/* HSI used as PLL clock source */
pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
}
pllp = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >>16) + 1 ) *2;
SystemCoreClock = pllvco/pllp;
break;
default:
SystemCoreClock = HSI_VALUE;
break;
}
/* Compute HCLK frequency --------------------------------------------------*/
/* Get HCLK prescaler */
tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
/* HCLK frequency */
SystemCoreClock >>= tmp;
}
/**
* @brief Configures the System clock source, PLL Multiplier and Divider factors,
* AHB/APBx prescalers and Flash settings
* @Note This function should be called only once the RCC clock configuration
* is reset to the default reset state (done in SystemInit() function).
* @param None
* @retval None
*/
static void SetSysClock(void)
{
/******************************************************************************/
/* PLL (clocked by HSE) used as System clock source */
/******************************************************************************/
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
/* Enable HSE */
RCC->CR |= ((uint32_t)RCC_CR_HSEON);
/* Wait till HSE is ready and if Time out is reached exit */
do
{
HSEStatus = RCC->CR & RCC_CR_HSERDY;
StartUpCounter++;
} while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
if ((RCC->CR & RCC_CR_HSERDY) != RESET)
{
HSEStatus = (uint32_t)0x01;
}
else
{
HSEStatus = (uint32_t)0x00;
}
if (HSEStatus == (uint32_t)0x01)
{
/* Select regulator voltage output Scale 1 mode, System frequency up to 168 MHz */
RCC->APB1ENR |= RCC_APB1ENR_PWREN;
PWR->CR |= PWR_CR_VOS;
/* HCLK = SYSCLK / 1*/
RCC->CFGR |= RCC_CFGR_HPRE_DIV1;
/* PCLK2 = HCLK / 2*/
RCC->CFGR |= RCC_CFGR_PPRE2_DIV2;
/* PCLK1 = HCLK / 4*/
RCC->CFGR |= RCC_CFGR_PPRE1_DIV4;
/* Configure the main PLL */
RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) |
(RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24);
/* Enable the main PLL */
RCC->CR |= RCC_CR_PLLON;
/* Wait till the main PLL is ready */
while((RCC->CR & RCC_CR_PLLRDY) == 0)
{
}
/* Configure Flash prefetch, Instruction cache, Data cache and wait state */
FLASH->ACR = FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_5WS;
/* Select the main PLL as system clock source */
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
RCC->CFGR |= RCC_CFGR_SW_PLL;
/* Wait till the main PLL is used as system clock source */
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL);
{
}
}
else
{ /* If HSE fails to start-up, the application will have wrong clock
configuration. User can add here some code to deal with this error */
}
}
/**
* @brief Setup the external memory controller. Called in startup_stm32f4xx.s
* before jump to __main
* @param None
* @retval None
*/
#ifdef DATA_IN_ExtSRAM
/**
* @brief Setup the external memory controller.
* Called in startup_stm32f4xx.s before jump to main.
* This function configures the external SRAM mounted on STM324xG_EVAL/STM324x7I boards
* This SRAM will be used as program data memory (including heap and stack).
* @param None
* @retval None
*/
void SystemInit_ExtMemCtl(void)
{
/*-- GPIOs Configuration -----------------------------------------------------*/
/*
+-------------------+--------------------+------------------+------------------+
+ SRAM pins assignment +
+-------------------+--------------------+------------------+------------------+
| PD0 <-> FSMC_D2 | PE0 <-> FSMC_NBL0 | PF0 <-> FSMC_A0 | PG0 <-> FSMC_A10 |
| PD1 <-> FSMC_D3 | PE1 <-> FSMC_NBL1 | PF1 <-> FSMC_A1 | PG1 <-> FSMC_A11 |
| PD4 <-> FSMC_NOE | PE2 <-> FSMC_A23 | PF2 <-> FSMC_A2 | PG2 <-> FSMC_A12 |
| PD5 <-> FSMC_NWE | PE3 <-> FSMC_A19 | PF3 <-> FSMC_A3 | PG3 <-> FSMC_A13 |
| PD8 <-> FSMC_D13 | PE4 <-> FSMC_A20 | PF4 <-> FSMC_A4 | PG4 <-> FSMC_A14 |
| PD9 <-> FSMC_D14 | PE5 <-> FSMC_A21 | PF5 <-> FSMC_A5 | PG5 <-> FSMC_A15 |
| PD10 <-> FSMC_D15 | PE6 <-> FSMC_A22 | PF12 <-> FSMC_A6 | PG9 <-> FSMC_NE2 |
| PD11 <-> FSMC_A16 | PE7 <-> FSMC_D4 | PF13 <-> FSMC_A7 |------------------+
| PD12 <-> FSMC_A17 | PE8 <-> FSMC_D5 | PF14 <-> FSMC_A8 |
| PD13 <-> FSMC_A18 | PE9 <-> FSMC_D6 | PF15 <-> FSMC_A9 |
| PD14 <-> FSMC_D0 | PE10 <-> FSMC_D7 |------------------+
| PD15 <-> FSMC_D1 | PE11 <-> FSMC_D8 |
+-------------------| PE12 <-> FSMC_D9 |
| PE13 <-> FSMC_D10 |
| PE14 <-> FSMC_D11 |
| PE15 <-> FSMC_D12 |
+--------------------+
*/
/* Enable GPIOD, GPIOE, GPIOF and GPIOG interface clock */
RCC->AHB1ENR |= 0x00000078;
/* Connect PDx pins to FSMC Alternate function */
GPIOD->AFR[0] = 0x00cc00cc;
GPIOD->AFR[1] = 0xcccccccc;
/* Configure PDx pins in Alternate function mode */
GPIOD->MODER = 0xaaaa0a0a;
/* Configure PDx pins speed to 100 MHz */
GPIOD->OSPEEDR = 0xffff0f0f;
/* Configure PDx pins Output type to push-pull */
GPIOD->OTYPER = 0x00000000;
/* No pull-up, pull-down for PDx pins */
GPIOD->PUPDR = 0x00000000;
/* Connect PEx pins to FSMC Alternate function */
GPIOE->AFR[0] = 0xcccccccc;
GPIOE->AFR[1] = 0xcccccccc;
/* Configure PEx pins in Alternate function mode */
GPIOE->MODER = 0xaaaaaaaa;
/* Configure PEx pins speed to 100 MHz */
GPIOE->OSPEEDR = 0xffffffff;
/* Configure PEx pins Output type to push-pull */
GPIOE->OTYPER = 0x00000000;
/* No pull-up, pull-down for PEx pins */
GPIOE->PUPDR = 0x00000000;
/* Connect PFx pins to FSMC Alternate function */
GPIOF->AFR[0] = 0x00cccccc;
GPIOF->AFR[1] = 0xcccc0000;
/* Configure PFx pins in Alternate function mode */
GPIOF->MODER = 0xaa000aaa;
/* Configure PFx pins speed to 100 MHz */
GPIOF->OSPEEDR = 0xff000fff;
/* Configure PFx pins Output type to push-pull */
GPIOF->OTYPER = 0x00000000;
/* No pull-up, pull-down for PFx pins */
GPIOF->PUPDR = 0x00000000;
/* Connect PGx pins to FSMC Alternate function */
GPIOG->AFR[0] = 0x00cccccc;
GPIOG->AFR[1] = 0x000000c0;
/* Configure PGx pins in Alternate function mode */
GPIOG->MODER = 0x00080aaa;
/* Configure PGx pins speed to 100 MHz */
GPIOG->OSPEEDR = 0x000c0fff;
/* Configure PGx pins Output type to push-pull */
GPIOG->OTYPER = 0x00000000;
/* No pull-up, pull-down for PGx pins */
GPIOG->PUPDR = 0x00000000;
/*-- FSMC Configuration ------------------------------------------------------*/
/* Enable the FSMC interface clock */
RCC->AHB3ENR |= 0x00000001;
/* Configure and enable Bank1_SRAM2 */
FSMC_Bank1->BTCR[2] = 0x00001011;
FSMC_Bank1->BTCR[3] = 0x00000201;
FSMC_Bank1E->BWTR[2] = 0x0fffffff;
/*
Bank1_SRAM2 is configured as follow:
p.FSMC_AddressSetupTime = 1;
p.FSMC_AddressHoldTime = 0;
p.FSMC_DataSetupTime = 2;
p.FSMC_BusTurnAroundDuration = 0;
p.FSMC_CLKDivision = 0;
p.FSMC_DataLatency = 0;
p.FSMC_AccessMode = FSMC_AccessMode_A;
FSMC_NORSRAMInitStructure.FSMC_Bank = FSMC_Bank1_NORSRAM2;
FSMC_NORSRAMInitStructure.FSMC_DataAddressMux = FSMC_DataAddressMux_Disable;
FSMC_NORSRAMInitStructure.FSMC_MemoryType = FSMC_MemoryType_SRAM;
FSMC_NORSRAMInitStructure.FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_16b;
FSMC_NORSRAMInitStructure.FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable;
FSMC_NORSRAMInitStructure.FSMC_AsynchronousWait = FSMC_AsynchronousWait_Disable;
FSMC_NORSRAMInitStructure.FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low;
FSMC_NORSRAMInitStructure.FSMC_WrapMode = FSMC_WrapMode_Disable;
FSMC_NORSRAMInitStructure.FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState;
FSMC_NORSRAMInitStructure.FSMC_WriteOperation = FSMC_WriteOperation_Enable;
FSMC_NORSRAMInitStructure.FSMC_WaitSignal = FSMC_WaitSignal_Disable;
FSMC_NORSRAMInitStructure.FSMC_ExtendedMode = FSMC_ExtendedMode_Disable;
FSMC_NORSRAMInitStructure.FSMC_WriteBurst = FSMC_WriteBurst_Disable;
FSMC_NORSRAMInitStructure.FSMC_ReadWriteTimingStruct = &p;
FSMC_NORSRAMInitStructure.FSMC_WriteTimingStruct = &p;
*/
}
#endif /* DATA_IN_ExtSRAM */
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

View File

@ -0,0 +1,50 @@
BOARD_TYPE := 0x09
BOARD_REVISION := 0x03
BOOTLOADER_VERSION := 0x06
HW_TYPE := 0x00
MCU := cortex-m4
CHIP := STM32F407VGT
BOARD := STM32F4xx_DI
MODEL := HD
MODEL_SUFFIX :=
OPENOCD_JTAG_CONFIG := stlink-v2.cfg
OPENOCD_CONFIG := stm32f4xx.stlink.cfg
# Flash memory map for Revolution:
# Sector start size use
# 0 0x0800 0000 16k BL
# 1 0x0800 4000 16k BL
# 2 0x0800 8000 16k EE
# 3 0x0800 C000 16k EE
# 4 0x0801 0000 64k Unused
# 5 0x0802 0000 128k FW
# 6 0x0804 0000 128k FW
# 7 0x0806 0000 128k FW
# 8 0x0808 0000 128k Unused
# 9 0x080A 0000 128k Unused
# 10 0x080C 0000 128k Unused ..
# 11 0x080E 0000 128k Unused
# Note: These must match the values in link_$(BOARD)_memory.ld
BL_BANK_BASE := 0x08000000 # Start of bootloader flash
BL_BANK_SIZE := 0x00008000 # Should include BD_INFO region
# 16KB for settings storage
EE_BANK_BASE := 0x08008000 # EEPROM storage area
EE_BANK_SIZE := 0x00008000 # Size of EEPROM storage area
USER_EE_BANK_BASE := 0x080C0000 # EEPROM storage area
USER_EE_BANK_SIZE := 0x00040000 # Size of EEPROM storage area
# Leave the remaining 64KB sectors for other uses
FW_BANK_BASE := 0x08020000 # Start of firmware flash
FW_BANK_SIZE := 0x000A0000 # Should include FW_DESC_SIZE
FW_DESC_SIZE := 0x00000064
OSCILLATOR_FREQ := 8000000
SYSCLK_FREQ := 168000000

View File

@ -0,0 +1,1812 @@
/**
******************************************************************************
* @file board_hw_defs.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
* @author PhoenixPilot, http://github.com/PhoenixPilot, Copyright (C) 2012
* @addtogroup OpenPilotSystem OpenPilot System
* @{
* @addtogroup OpenPilotCore OpenPilot Core
* @{
* @brief Defines board specific static initializers for hardware for the Revolution board.
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#if defined(PIOS_INCLUDE_LED)
#include <pios_led_priv.h>
static const struct pios_gpio pios_leds[] = {
[PIOS_LED_HEARTBEAT] = {
.pin = {
.gpio = GPIOD,
.init = {
.GPIO_Pin = GPIO_Pin_15,
.GPIO_Speed = GPIO_Speed_50MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.active_low = false
},
[PIOS_LED_ALARM] = {
.pin = {
.gpio = GPIOD,
.init = {
.GPIO_Pin = GPIO_Pin_14,
.GPIO_Speed = GPIO_Speed_50MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.active_low = false
},
[PIOS_LED_D1] = {
.pin = {
.gpio = GPIOD,
.init = {
.GPIO_Pin = GPIO_Pin_13,
.GPIO_Speed = GPIO_Speed_50MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.active_low = false
},
[PIOS_LED_D2] = {
.pin = {
.gpio = GPIOD,
.init = {
.GPIO_Pin = GPIO_Pin_12,
.GPIO_Speed = GPIO_Speed_50MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.active_low = false
},
};
static const struct pios_gpio_cfg pios_led_cfg = {
.gpios = pios_leds,
.num_gpios = NELEMENTS(pios_leds),
};
const struct pios_gpio_cfg *PIOS_BOARD_HW_DEFS_GetLedCfg(__attribute__((unused)) uint32_t board_revision)
{
return &pios_led_cfg;
}
#endif /* PIOS_INCLUDE_LED */
#if defined(PIOS_INCLUDE_SPI)
#include <pios_spi_priv.h>
#if defined(PIOS_OVERO_SPI)
/* SPI2 Interface
* - Used for Flexi/IO/Overo communications
3: PB12 = SPI2 NSS, CAN2 RX
4: PB13 = SPI2 SCK, CAN2 TX, USART3 CTS
5: PB14 = SPI2 MISO, TIM12 CH1, USART3 RTS
6: PB15 = SPI2 MOSI, TIM12 CH2
*/
#include <pios_overo_priv.h>
void PIOS_OVERO_irq_handler(void);
void DMA1_Stream7_IRQHandler(void) __attribute__((alias("PIOS_OVERO_irq_handler")));
static const struct pios_overo_cfg pios_overo_cfg = {
.regs = SPI2,
.remap = GPIO_AF_SPI2,
.init = {
.SPI_Mode = SPI_Mode_Slave,
.SPI_Direction = SPI_Direction_2Lines_FullDuplex,
.SPI_DataSize = SPI_DataSize_8b,
.SPI_NSS = SPI_NSS_Hard,
.SPI_FirstBit = SPI_FirstBit_MSB,
.SPI_CRCPolynomial = 7,
.SPI_CPOL = SPI_CPOL_High,
.SPI_CPHA = SPI_CPHA_2Edge,
.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2,
},
.use_crc = false,
.dma = {
.irq = {
// Note this is the stream ID that triggers interrupts (in this case TX)
.flags = (DMA_IT_TCIF7),
.init = {
.NVIC_IRQChannel = DMA1_Stream7_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.channel = DMA1_Stream0,
.init = {
.DMA_Channel = DMA_Channel_0,
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI2->DR),
.DMA_DIR = DMA_DIR_PeripheralToMemory,
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
.DMA_MemoryInc = DMA_MemoryInc_Enable,
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
.DMA_Mode = DMA_Mode_Circular,
.DMA_Priority = DMA_Priority_Medium,
// TODO: Enable FIFO
.DMA_FIFOMode = DMA_FIFOMode_Disable,
.DMA_FIFOThreshold = DMA_FIFOThreshold_Full,
.DMA_MemoryBurst = DMA_MemoryBurst_Single,
.DMA_PeripheralBurst = DMA_PeripheralBurst_Single,
},
},
.tx = {
.channel = DMA1_Stream7,
.init = {
.DMA_Channel = DMA_Channel_0,
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI2->DR),
.DMA_DIR = DMA_DIR_MemoryToPeripheral,
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
.DMA_MemoryInc = DMA_MemoryInc_Enable,
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
.DMA_Mode = DMA_Mode_Circular,
.DMA_Priority = DMA_Priority_Medium,
.DMA_FIFOMode = DMA_FIFOMode_Disable,
.DMA_FIFOThreshold = DMA_FIFOThreshold_Full,
.DMA_MemoryBurst = DMA_MemoryBurst_Single,
.DMA_PeripheralBurst = DMA_PeripheralBurst_Single,
},
},
},
.sclk = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_13,
.GPIO_Speed = GPIO_Speed_100MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_NOPULL
},
},
.miso = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_14,
.GPIO_Speed = GPIO_Speed_50MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_NOPULL
},
},
.mosi = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_15,
.GPIO_Speed = GPIO_Speed_50MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_NOPULL
},
},
.slave_count = 1,
.ssel = {
{
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_12,
.GPIO_Speed = GPIO_Speed_50MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
}
},
};
uint32_t pios_overo_id = 0;
void PIOS_OVERO_irq_handler(void)
{
/* Call into the generic code to handle the IRQ for this specific device */
PIOS_OVERO_DMA_irq_handler(pios_overo_id);
}
#endif /* PIOS_OVERO_SPI */
/*
* SPI1 Interface
* Used for MPU6000 gyro and accelerometer
*/
void PIOS_SPI_gyro_irq_handler(void);
void DMA2_Stream0_IRQHandler(void) __attribute__((alias("PIOS_SPI_gyro_irq_handler")));
void DMA2_Stream3_IRQHandler(void) __attribute__((alias("PIOS_SPI_gyro_irq_handler")));
static const struct pios_spi_cfg pios_spi_gyro_cfg = {
.regs = SPI1,
.remap = GPIO_AF_SPI1,
.init = {
.SPI_Mode = SPI_Mode_Master,
.SPI_Direction = SPI_Direction_2Lines_FullDuplex,
.SPI_DataSize = SPI_DataSize_8b,
.SPI_NSS = SPI_NSS_Soft,
.SPI_FirstBit = SPI_FirstBit_MSB,
.SPI_CRCPolynomial = 7,
.SPI_CPOL = SPI_CPOL_High,
.SPI_CPHA = SPI_CPHA_2Edge,
.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_16,
},
.use_crc = false,
.dma = {
.irq = {
.flags = (DMA_IT_TCIF0 | DMA_IT_TEIF0 | DMA_IT_HTIF0),
.init = {
.NVIC_IRQChannel = DMA2_Stream0_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.channel = DMA2_Stream0,
.init = {
.DMA_Channel = DMA_Channel_3,
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR),
.DMA_DIR = DMA_DIR_PeripheralToMemory,
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
.DMA_MemoryInc = DMA_MemoryInc_Enable,
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
.DMA_Mode = DMA_Mode_Normal,
.DMA_Priority = DMA_Priority_Medium,
.DMA_FIFOMode = DMA_FIFOMode_Disable,
/* .DMA_FIFOThreshold */
.DMA_MemoryBurst = DMA_MemoryBurst_Single,
.DMA_PeripheralBurst = DMA_PeripheralBurst_Single,
},
},
.tx = {
.channel = DMA2_Stream3,
.init = {
.DMA_Channel = DMA_Channel_3,
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR),
.DMA_DIR = DMA_DIR_MemoryToPeripheral,
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
.DMA_MemoryInc = DMA_MemoryInc_Enable,
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
.DMA_Mode = DMA_Mode_Normal,
.DMA_Priority = DMA_Priority_High,
.DMA_FIFOMode = DMA_FIFOMode_Disable,
/* .DMA_FIFOThreshold */
.DMA_MemoryBurst = DMA_MemoryBurst_Single,
.DMA_PeripheralBurst = DMA_PeripheralBurst_Single,
},
},
},
.sclk = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_5,
.GPIO_Speed = GPIO_Speed_100MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.miso = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_6,
.GPIO_Speed = GPIO_Speed_50MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.mosi = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_7,
.GPIO_Speed = GPIO_Speed_50MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.slave_count = 1,
.ssel = {
{
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_4,
.GPIO_Speed = GPIO_Speed_50MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
}
}
}
};
static uint32_t pios_spi_gyro_id;
void PIOS_SPI_gyro_irq_handler(void)
{
/* Call into the generic code to handle the IRQ for this specific device */
PIOS_SPI_IRQ_Handler(pios_spi_gyro_id);
}
#if false
/*
* SPI3 Interface
* Used for Flash and the RFM22B
*/
void PIOS_SPI_telem_flash_irq_handler(void);
void DMA1_Stream0_IRQHandler(void) __attribute__((alias("PIOS_SPI_telem_flash_irq_handler")));
void DMA1_Stream5_IRQHandler(void) __attribute__((alias("PIOS_SPI_telem_flash_irq_handler")));
static const struct pios_spi_cfg pios_spi_telem_flash_cfg = {
.regs = SPI3,
.remap = GPIO_AF_SPI3,
.init = {
.SPI_Mode = SPI_Mode_Master,
.SPI_Direction = SPI_Direction_2Lines_FullDuplex,
.SPI_DataSize = SPI_DataSize_8b,
.SPI_NSS = SPI_NSS_Soft,
.SPI_FirstBit = SPI_FirstBit_MSB,
.SPI_CRCPolynomial = 7,
.SPI_CPOL = SPI_CPOL_Low,
.SPI_CPHA = SPI_CPHA_1Edge,
.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8,
},
.use_crc = false,
.dma = {
.irq = {
// Note this is the stream ID that triggers interrupts (in this case RX)
.flags = (DMA_IT_TCIF0 | DMA_IT_TEIF0 | DMA_IT_HTIF0),
.init = {
.NVIC_IRQChannel = DMA1_Stream0_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.channel = DMA1_Stream0,
.init = {
.DMA_Channel = DMA_Channel_0,
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI3->DR),
.DMA_DIR = DMA_DIR_PeripheralToMemory,
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
.DMA_MemoryInc = DMA_MemoryInc_Enable,
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
.DMA_Mode = DMA_Mode_Normal,
.DMA_Priority = DMA_Priority_Medium,
// TODO: Enable FIFO
.DMA_FIFOMode = DMA_FIFOMode_Disable,
.DMA_FIFOThreshold = DMA_FIFOThreshold_Full,
.DMA_MemoryBurst = DMA_MemoryBurst_Single,
.DMA_PeripheralBurst = DMA_PeripheralBurst_Single,
},
},
.tx = {
.channel = DMA1_Stream5,
.init = {
.DMA_Channel = DMA_Channel_0,
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI3->DR),
.DMA_DIR = DMA_DIR_MemoryToPeripheral,
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
.DMA_MemoryInc = DMA_MemoryInc_Enable,
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
.DMA_Mode = DMA_Mode_Normal,
.DMA_Priority = DMA_Priority_Medium,
.DMA_FIFOMode = DMA_FIFOMode_Disable,
.DMA_FIFOThreshold = DMA_FIFOThreshold_Full,
.DMA_MemoryBurst = DMA_MemoryBurst_Single,
.DMA_PeripheralBurst = DMA_PeripheralBurst_Single,
},
},
},
.sclk = {
.gpio = GPIOC,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Speed = GPIO_Speed_100MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_NOPULL
},
},
.miso = {
.gpio = GPIOC,
.init = {
.GPIO_Pin = GPIO_Pin_11,
.GPIO_Speed = GPIO_Speed_50MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_NOPULL
},
},
.mosi = {
.gpio = GPIOC,
.init = {
.GPIO_Pin = GPIO_Pin_12,
.GPIO_Speed = GPIO_Speed_50MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_NOPULL
},
},
.slave_count = 2,
.ssel = {
{ // RFM22b
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_15,
.GPIO_Speed = GPIO_Speed_50MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
}
},
{ // Flash
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_3,
.GPIO_Speed = GPIO_Speed_50MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
}
},
},
};
uint32_t pios_spi_telem_flash_id;
void PIOS_SPI_telem_flash_irq_handler(void)
{
/* Call into the generic code to handle the IRQ for this specific device */
PIOS_SPI_IRQ_Handler(pios_spi_telem_flash_id);
}
#if defined(PIOS_INCLUDE_RFM22B)
#include <pios_rfm22b_priv.h>
static const struct pios_exti_cfg pios_exti_rfm22b_cfg __exti_config = {
.vector = PIOS_RFM22_EXT_Int,
.line = EXTI_Line2,
.pin = {
.gpio = GPIOD,
.init = {
.GPIO_Pin = GPIO_Pin_2,
.GPIO_Speed = GPIO_Speed_100MHz,
.GPIO_Mode = GPIO_Mode_IN,
.GPIO_OType = GPIO_OType_OD,
.GPIO_PuPd = GPIO_PuPd_NOPULL,
},
},
.irq = {
.init = {
.NVIC_IRQChannel = EXTI2_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.exti = {
.init = {
.EXTI_Line = EXTI_Line2, // matches above GPIO pin
.EXTI_Mode = EXTI_Mode_Interrupt,
.EXTI_Trigger = EXTI_Trigger_Falling,
.EXTI_LineCmd = ENABLE,
},
},
};
const struct pios_rfm22b_cfg pios_rfm22b_rm1_cfg = {
.spi_cfg = &pios_spi_telem_flash_cfg,
.exti_cfg = &pios_exti_rfm22b_cfg,
.RFXtalCap = 0x7f,
.slave_num = 0,
.gpio_direction = GPIO0_RX_GPIO1_TX,
};
const struct pios_rfm22b_cfg pios_rfm22b_rm2_cfg = {
.spi_cfg = &pios_spi_telem_flash_cfg,
.exti_cfg = &pios_exti_rfm22b_cfg,
.RFXtalCap = 0x7f,
.slave_num = 0,
.gpio_direction = GPIO0_TX_GPIO1_RX,
};
const struct pios_rfm22b_cfg *PIOS_BOARD_HW_DEFS_GetRfm22Cfg(uint32_t board_revision)
{
switch (board_revision) {
case 2:
return &pios_rfm22b_rm1_cfg;
break;
case 3:
return &pios_rfm22b_rm2_cfg;
break;
default:
PIOS_DEBUG_Assert(0);
}
return NULL;
}
#endif /* PIOS_INCLUDE_RFM22B */
#endif /* false */
#endif /* PIOS_INCLUDE_SPI */
#if defined(PIOS_INCLUDE_FLASH)
#include "pios_flashfs_logfs_priv.h"
#include "pios_flash_jedec_priv.h"
#include "pios_flash_internal_priv.h"
static const struct flashfs_logfs_cfg flashfs_external_cfg = {
.fs_magic = 0x99abceef,
.total_fs_size = 0x00200000, /* 2M bytes (32 sectors = entire chip) */
.arena_size = 0x00010000, /* 256 * slot size */
.slot_size = 0x00000100, /* 256 bytes */
.start_offset = 0, /* start at the beginning of the chip */
.sector_size = 0x00010000, /* 64K bytes */
.page_size = 0x00000100, /* 256 bytes */
};
static const struct pios_flash_internal_cfg flash_internal_system_cfg = {};
static const struct flashfs_logfs_cfg flashfs_internal_cfg = {
.fs_magic = 0x99abcfef,
.total_fs_size = EE_BANK_SIZE, /* 32K bytes (2x16KB sectors) */
.arena_size = 0x00004000, /* 64 * slot size = 16K bytes = 1 sector */
.slot_size = 0x00000100, /* 256 bytes */
.start_offset = EE_BANK_BASE, /* start after the bootloader */
.sector_size = 0x00004000, /* 16K bytes */
.page_size = 0x00004000, /* 16K bytes */
};
static const struct flashfs_logfs_cfg flashfs_internal_user_cfg = {
.fs_magic = 0x99abcfef,
.total_fs_size = USER_EE_BANK_SIZE, /* 128K bytes (2x16KB sectors) */
.arena_size = 0x00020000, /* 64 * slot size = 16K bytes = 1 sector */
.slot_size = 0x00000100, /* 256 bytes */
.start_offset = USER_EE_BANK_BASE, /* start after the bootloader */
.sector_size = 0x00020000, /* 128K bytes */
.page_size = 0x00020000, /* 128K bytes */
};
#endif /* PIOS_INCLUDE_FLASH */
#include <pios_usart_priv.h>
#ifdef PIOS_INCLUDE_COM_TELEM
/*
* MAIN USART
*/
static const struct pios_usart_cfg pios_usart_main_cfg = {
.regs = USART1,
.remap = GPIO_AF_USART1,
.init = {
.USART_BaudRate = 57600,
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1,
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
},
.irq = {
.init = {
.NVIC_IRQChannel = USART1_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.tx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_9,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
};
#endif /* PIOS_INCLUDE_COM_TELEM */
#ifdef PIOS_INCLUDE_DSM
#include "pios_dsm_priv.h"
static const struct pios_usart_cfg pios_usart_dsm_main_cfg = {
.regs = USART1,
.remap = GPIO_AF_USART1,
.init = {
.USART_BaudRate = 115200,
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1,
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
.USART_Mode = USART_Mode_Rx,
},
.irq = {
.init = {
.NVIC_IRQChannel = USART1_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.tx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_9,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
};
// Because of the inverter on the main port this will not
// work. Notice the mode is set to IN to maintain API
// compatibility but protect the pins
static const struct pios_dsm_cfg pios_dsm_main_cfg = {
.bind = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_IN,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_NOPULL
},
},
};
#endif /* PIOS_INCLUDE_DSM */
#include <pios_sbus_priv.h>
#if defined(PIOS_INCLUDE_SBUS)
/*
* S.Bus USART
*/
#include <pios_sbus_priv.h>
static const struct pios_usart_cfg pios_usart_sbus_main_cfg = {
.regs = USART1,
.remap = GPIO_AF_USART1,
.init = {
.USART_BaudRate = 100000,
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_Even,
.USART_StopBits = USART_StopBits_2,
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
.USART_Mode = USART_Mode_Rx,
},
.irq = {
.init = {
.NVIC_IRQChannel = USART1_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.tx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_9,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_NOPULL
},
},
};
#endif /* PIOS_INCLUDE_SBUS */
// Need this defined regardless to be able to turn it off
static const struct pios_sbus_cfg pios_sbus_cfg = {
/* Inverter configuration */
.inv = {
.gpio = GPIOC,
.init = {
.GPIO_Pin = GPIO_Pin_0,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.gpio_inv_enable = Bit_SET,
.gpio_inv_disable = Bit_RESET,
.gpio_clk_func = RCC_AHB1PeriphClockCmd,
.gpio_clk_periph = RCC_AHB1Periph_GPIOC,
};
#ifdef PIOS_INCLUDE_COM_FLEXI
/*
* FLEXI PORT
*/
static const struct pios_usart_cfg pios_usart_flexi_cfg = {
.regs = USART3,
.remap = GPIO_AF_USART3,
.init = {
.USART_BaudRate = 57600,
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1,
.USART_HardwareFlowControl =
USART_HardwareFlowControl_None,
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
},
.irq = {
.init = {
.NVIC_IRQChannel = USART3_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_11,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.tx = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
};
#endif /* PIOS_INCLUDE_COM_FLEXI */
#ifdef PIOS_INCLUDE_DSM
#include "pios_dsm_priv.h"
static const struct pios_usart_cfg pios_usart_dsm_flexi_cfg = {
.regs = USART3,
.remap = GPIO_AF_USART3,
.init = {
.USART_BaudRate = 115200,
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1,
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
.USART_Mode = USART_Mode_Rx,
},
.irq = {
.init = {
.NVIC_IRQChannel = USART3_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_11,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.tx = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
};
static const struct pios_dsm_cfg pios_dsm_flexi_cfg = {
.bind = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_11,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_OUT,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_NOPULL
},
},
};
#endif /* PIOS_INCLUDE_DSM */
/*
* HK OSD
*/
static const struct pios_usart_cfg pios_usart_hkosd_main_cfg = {
.regs = USART1,
.remap = GPIO_AF_USART1,
.init = {
.USART_BaudRate = 57600,
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1,
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
},
.irq = {
.init = {
.NVIC_IRQChannel = USART1_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.tx = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_9,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
};
static const struct pios_usart_cfg pios_usart_hkosd_flexi_cfg = {
.regs = USART3,
.remap = GPIO_AF_USART3,
.init = {
.USART_BaudRate = 57600,
.USART_WordLength = USART_WordLength_8b,
.USART_Parity = USART_Parity_No,
.USART_StopBits = USART_StopBits_1,
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
},
.irq = {
.init = {
.NVIC_IRQChannel = USART3_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_11,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
.tx = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
},
};
#if defined(PIOS_INCLUDE_COM)
#include <pios_com_priv.h>
#endif /* PIOS_INCLUDE_COM */
#if defined(PIOS_INCLUDE_I2C)
#include <pios_i2c_priv.h>
/*
* I2C Adapters
*/
void PIOS_I2C_mag_pressure_adapter_ev_irq_handler(void);
void PIOS_I2C_mag_pressureadapter_er_irq_handler(void);
void I2C1_EV_IRQHandler()
__attribute__((alias("PIOS_I2C_mag_pressure_adapter_ev_irq_handler")));
void I2C1_ER_IRQHandler()
__attribute__((alias("PIOS_I2C_mag_pressure_adapter_er_irq_handler")));
static const struct pios_i2c_adapter_cfg pios_i2c_mag_pressure_adapter_cfg = {
.regs = I2C1,
.remap = GPIO_AF_I2C1,
.init = {
.I2C_Mode = I2C_Mode_I2C,
.I2C_OwnAddress1 = 0,
.I2C_Ack = I2C_Ack_Enable,
.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit,
.I2C_DutyCycle = I2C_DutyCycle_2,
.I2C_ClockSpeed = 400000, /* bits/s */
},
.transfer_timeout_ms = 50,
.scl = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_8,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_Speed = GPIO_Speed_50MHz,
.GPIO_OType = GPIO_OType_OD,
.GPIO_PuPd = GPIO_PuPd_NOPULL,
},
},
.sda = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_9,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_Speed = GPIO_Speed_50MHz,
.GPIO_OType = GPIO_OType_OD,
.GPIO_PuPd = GPIO_PuPd_NOPULL,
},
},
.event = {
.flags = 0, /* FIXME: check this */
.init = {
.NVIC_IRQChannel = I2C1_EV_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.error = {
.flags = 0, /* FIXME: check this */
.init = {
.NVIC_IRQChannel = I2C1_ER_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
};
uint32_t pios_i2c_mag_pressure_adapter_id;
void PIOS_I2C_mag_pressure_adapter_ev_irq_handler(void)
{
/* Call into the generic code to handle the IRQ for this specific device */
PIOS_I2C_EV_IRQ_Handler(pios_i2c_mag_pressure_adapter_id);
}
void PIOS_I2C_mag_pressure_adapter_er_irq_handler(void)
{
/* Call into the generic code to handle the IRQ for this specific device */
PIOS_I2C_ER_IRQ_Handler(pios_i2c_mag_pressure_adapter_id);
}
void PIOS_I2C_flexiport_adapter_ev_irq_handler(void);
void PIOS_I2C_flexiport_adapter_er_irq_handler(void);
void I2C2_EV_IRQHandler() __attribute__((alias("PIOS_I2C_flexiport_adapter_ev_irq_handler")));
void I2C2_ER_IRQHandler() __attribute__((alias("PIOS_I2C_flexiport_adapter_er_irq_handler")));
static const struct pios_i2c_adapter_cfg pios_i2c_flexiport_adapter_cfg = {
.regs = I2C2,
.remap = GPIO_AF_I2C2,
.init = {
.I2C_Mode = I2C_Mode_I2C,
.I2C_OwnAddress1 = 0,
.I2C_Ack = I2C_Ack_Enable,
.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit,
.I2C_DutyCycle = I2C_DutyCycle_2,
.I2C_ClockSpeed = 400000, /* bits/s */
},
.transfer_timeout_ms = 50,
.scl = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_10,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_Speed = GPIO_Speed_50MHz,
.GPIO_OType = GPIO_OType_OD,
.GPIO_PuPd = GPIO_PuPd_NOPULL,
},
},
.sda = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_11,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_Speed = GPIO_Speed_50MHz,
.GPIO_OType = GPIO_OType_OD,
.GPIO_PuPd = GPIO_PuPd_NOPULL,
},
},
.event = {
.flags = 0, /* FIXME: check this */
.init = {
.NVIC_IRQChannel = I2C2_EV_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.error = {
.flags = 0, /* FIXME: check this */
.init = {
.NVIC_IRQChannel = I2C2_ER_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
};
uint32_t pios_i2c_flexiport_adapter_id;
void PIOS_I2C_flexiport_adapter_ev_irq_handler(void)
{
/* Call into the generic code to handle the IRQ for this specific device */
PIOS_I2C_EV_IRQ_Handler(pios_i2c_flexiport_adapter_id);
}
void PIOS_I2C_flexiport_adapter_er_irq_handler(void)
{
/* Call into the generic code to handle the IRQ for this specific device */
PIOS_I2C_ER_IRQ_Handler(pios_i2c_flexiport_adapter_id);
}
void PIOS_I2C_pressure_adapter_ev_irq_handler(void);
void PIOS_I2C_pressure_adapter_er_irq_handler(void);
#endif /* PIOS_INCLUDE_I2C */
#if defined(PIOS_INCLUDE_RTC)
/*
* Realtime Clock (RTC)
*/
#include <pios_rtc_priv.h>
void PIOS_RTC_IRQ_Handler(void);
void RTC_WKUP_IRQHandler() __attribute__((alias("PIOS_RTC_IRQ_Handler")));
static const struct pios_rtc_cfg pios_rtc_main_cfg = {
.clksrc = RCC_RTCCLKSource_HSE_Div8, // Divide 8 Mhz crystal down to 1
// For some reason it's acting like crystal is 16 Mhz. This clock is then divided
// by another 16 to give a nominal 62.5 khz clock
.prescaler = 100, // Every 100 cycles gives 625 Hz
.irq = {
.init = {
.NVIC_IRQChannel = RTC_WKUP_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
};
void PIOS_RTC_IRQ_Handler(void)
{
PIOS_RTC_irq_handler();
}
#endif /* if defined(PIOS_INCLUDE_RTC) */
#include "pios_tim_priv.h"
static const TIM_TimeBaseInitTypeDef tim_3_5_time_base = {
.TIM_Prescaler = (PIOS_PERIPHERAL_APB1_CLOCK / 1000000) - 1,
.TIM_ClockDivision = TIM_CKD_DIV1,
.TIM_CounterMode = TIM_CounterMode_Up,
.TIM_Period = ((1000000 / PIOS_SERVO_UPDATE_HZ) - 1),
.TIM_RepetitionCounter = 0x0000,
};
static const TIM_TimeBaseInitTypeDef tim_9_10_11_time_base = {
.TIM_Prescaler = (PIOS_PERIPHERAL_APB2_CLOCK / 1000000) - 1,
.TIM_ClockDivision = TIM_CKD_DIV1,
.TIM_CounterMode = TIM_CounterMode_Up,
.TIM_Period = ((1000000 / PIOS_SERVO_UPDATE_HZ) - 1),
.TIM_RepetitionCounter = 0x0000,
};
static const struct pios_tim_clock_cfg tim_3_cfg = {
.timer = TIM3,
.time_base_init = &tim_3_5_time_base,
.irq = {
.init = {
.NVIC_IRQChannel = TIM3_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
};
static const struct pios_tim_clock_cfg tim_5_cfg = {
.timer = TIM5,
.time_base_init = &tim_3_5_time_base,
.irq = {
.init = {
.NVIC_IRQChannel = TIM5_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
};
static const struct pios_tim_clock_cfg tim_9_cfg = {
.timer = TIM9,
.time_base_init = &tim_9_10_11_time_base,
.irq = {
.init = {
.NVIC_IRQChannel = TIM1_BRK_TIM9_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
};
static const struct pios_tim_clock_cfg tim_10_cfg = {
.timer = TIM10,
.time_base_init = &tim_9_10_11_time_base,
.irq = {
.init = {
.NVIC_IRQChannel = TIM1_UP_TIM10_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
};
static const struct pios_tim_clock_cfg tim_11_cfg = {
.timer = TIM11,
.time_base_init = &tim_9_10_11_time_base,
.irq = {
.init = {
.NVIC_IRQChannel = TIM1_TRG_COM_TIM11_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
};
// Set up timers that only have inputs on APB1
// TIM2,3,4,5,6,7,12,13,14
static const TIM_TimeBaseInitTypeDef tim_apb1_time_base = {
.TIM_Prescaler = (PIOS_PERIPHERAL_APB1_CLOCK / 1000000) - 1,
.TIM_ClockDivision = TIM_CKD_DIV1,
.TIM_CounterMode = TIM_CounterMode_Up,
.TIM_Period = 0xFFFF,
.TIM_RepetitionCounter = 0x0000,
};
// Set up timers that only have inputs on APB2
// TIM1,8,9,10,11
static const TIM_TimeBaseInitTypeDef tim_apb2_time_base = {
.TIM_Prescaler = (PIOS_PERIPHERAL_APB2_CLOCK / 1000000) - 1,
.TIM_ClockDivision = TIM_CKD_DIV1,
.TIM_CounterMode = TIM_CounterMode_Up,
.TIM_Period = 0xFFFF,
.TIM_RepetitionCounter = 0x0000,
};
static const struct pios_tim_clock_cfg tim_1_cfg = {
.timer = TIM1,
.time_base_init = &tim_apb2_time_base,
.irq = {
.init = {
.NVIC_IRQChannel = TIM1_CC_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
};
static const struct pios_tim_clock_cfg tim_4_cfg = {
.timer = TIM4,
.time_base_init = &tim_apb1_time_base,
.irq = {
.init = {
.NVIC_IRQChannel = TIM4_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
};
static const struct pios_tim_clock_cfg tim_8_cfg = {
.timer = TIM8,
.time_base_init = &tim_apb2_time_base,
.irq = {
.init = {
.NVIC_IRQChannel = TIM8_CC_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
};
static const struct pios_tim_clock_cfg tim_12_cfg = {
.timer = TIM12,
.time_base_init = &tim_apb1_time_base,
.irq = {
.init = {
.NVIC_IRQChannel = TIM8_BRK_TIM12_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
};
/**
* Pios servo configuration structures
* Using TIM3, TIM9, TIM2, TIM5
*/
#include <pios_servo_priv.h>
static const struct pios_tim_channel pios_tim_servoport_all_pins[] = {
{
.timer = TIM3,
.timer_chan = TIM_Channel_3,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_0,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
.pin_source = GPIO_PinSource0,
},
.remap = GPIO_AF_TIM3,
},
{
.timer = TIM3,
.timer_chan = TIM_Channel_4,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_1,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
.pin_source = GPIO_PinSource1,
},
.remap = GPIO_AF_TIM3,
},
{
.timer = TIM9,
.timer_chan = TIM_Channel_2,
.pin = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_3,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
.pin_source = GPIO_PinSource3,
},
.remap = GPIO_AF_TIM9,
},
{
.timer = TIM2,
.timer_chan = TIM_Channel_3,
.pin = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_2,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
.pin_source = GPIO_PinSource2,
},
.remap = GPIO_AF_TIM2,
},
{
.timer = TIM5,
.timer_chan = TIM_Channel_2,
.pin = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_1,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
.pin_source = GPIO_PinSource1,
},
.remap = GPIO_AF_TIM5,
},
{
.timer = TIM5,
.timer_chan = TIM_Channel_1,
.pin = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_0,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
.pin_source = GPIO_PinSource0,
},
.remap = GPIO_AF_TIM5,
},
// PWM pins on FlexiIO(receiver) port
{
// * 6: PB15 = SPI2 MOSI, TIM12 CH2
.timer = TIM12,
.timer_chan = TIM_Channel_2,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_15,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
.pin_source = GPIO_PinSource15,
},
.remap = GPIO_AF_TIM12,
},
{
// * 7: PC6 = TIM8 CH1, USART6 TX
.timer = TIM8,
.timer_chan = TIM_Channel_1,
.pin = {
.gpio = GPIOC,
.init = {
.GPIO_Pin = GPIO_Pin_6,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
.pin_source = GPIO_PinSource6,
},
.remap = GPIO_AF_TIM8,
},
{
// * 8: PC7 = TIM8 CH2, USART6 RX
.timer = TIM8,
.timer_chan = TIM_Channel_2,
.pin = {
.gpio = GPIOC,
.init = {
.GPIO_Pin = GPIO_Pin_7,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
.pin_source = GPIO_PinSource7,
},
.remap = GPIO_AF_TIM8,
},
{
// * 9: PC8 = TIM8 CH3
.timer = TIM8,
.timer_chan = TIM_Channel_3,
.pin = {
.gpio = GPIOC,
.init = {
.GPIO_Pin = GPIO_Pin_8,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
.pin_source = GPIO_PinSource8,
},
.remap = GPIO_AF_TIM8,
},
{
// * 10: PC9 = TIM8 CH4
.timer = TIM8,
.timer_chan = TIM_Channel_4,
.pin = {
.gpio = GPIOC,
.init = {
.GPIO_Pin = GPIO_Pin_9,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
.pin_source = GPIO_PinSource9,
},
.remap = GPIO_AF_TIM8,
},
{
// * 5: PB14 = SPI2 MISO, TIM12 CH1, USART3 RTS
.timer = TIM12,
.timer_chan = TIM_Channel_1,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_14,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
.pin_source = GPIO_PinSource14,
},
.remap = GPIO_AF_TIM12,
},
};
#define PIOS_SERVOPORT_ALL_PINS_PWMOUT 6
#define PIOS_SERVOPORT_ALL_PINS_PWMOUT_IN_PPM 11
#define PIOS_SERVOPORT_ALL_PINS_PWMOUT_IN 12
const struct pios_servo_cfg pios_servo_cfg_out = {
.tim_oc_init = {
.TIM_OCMode = TIM_OCMode_PWM1,
.TIM_OutputState = TIM_OutputState_Enable,
.TIM_OutputNState = TIM_OutputNState_Disable,
.TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION,
.TIM_OCPolarity = TIM_OCPolarity_High,
.TIM_OCNPolarity = TIM_OCPolarity_High,
.TIM_OCIdleState = TIM_OCIdleState_Reset,
.TIM_OCNIdleState = TIM_OCNIdleState_Reset,
},
.channels = pios_tim_servoport_all_pins,
.num_channels = PIOS_SERVOPORT_ALL_PINS_PWMOUT,
};
// All servo outputs, servo input ch1 ppm, ch2-6 outputs
const struct pios_servo_cfg pios_servo_cfg_out_in_ppm = {
.tim_oc_init = {
.TIM_OCMode = TIM_OCMode_PWM1,
.TIM_OutputState = TIM_OutputState_Enable,
.TIM_OutputNState = TIM_OutputNState_Disable,
.TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION,
.TIM_OCPolarity = TIM_OCPolarity_High,
.TIM_OCNPolarity = TIM_OCPolarity_High,
.TIM_OCIdleState = TIM_OCIdleState_Reset,
.TIM_OCNIdleState = TIM_OCNIdleState_Reset,
},
.channels = pios_tim_servoport_all_pins,
.num_channels = PIOS_SERVOPORT_ALL_PINS_PWMOUT_IN_PPM,
};
// All servo outputs, servo inputs ch1-6 Outputs
const struct pios_servo_cfg pios_servo_cfg_out_in = {
.tim_oc_init = {
.TIM_OCMode = TIM_OCMode_PWM1,
.TIM_OutputState = TIM_OutputState_Enable,
.TIM_OutputNState = TIM_OutputNState_Disable,
.TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION,
.TIM_OCPolarity = TIM_OCPolarity_High,
.TIM_OCNPolarity = TIM_OCPolarity_High,
.TIM_OCIdleState = TIM_OCIdleState_Reset,
.TIM_OCNIdleState = TIM_OCNIdleState_Reset,
},
.channels = pios_tim_servoport_all_pins,
.num_channels = PIOS_SERVOPORT_ALL_PINS_PWMOUT_IN,
};
/*
* PWM Inputs
* TIM1, TIM8, TIM12
*/
#if defined(PIOS_INCLUDE_PWM) || defined(PIOS_INCLUDE_PPM)
#include <pios_pwm_priv.h>
static const struct pios_tim_channel pios_tim_rcvrport_all_channels[] = {
{
.timer = TIM12,
.timer_chan = TIM_Channel_1,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_14,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
.pin_source = GPIO_PinSource14,
},
.remap = GPIO_AF_TIM12,
},
{
.timer = TIM12,
.timer_chan = TIM_Channel_2,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_15,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
.pin_source = GPIO_PinSource15,
},
.remap = GPIO_AF_TIM12,
},
{
.timer = TIM8,
.timer_chan = TIM_Channel_1,
.pin = {
.gpio = GPIOC,
.init = {
.GPIO_Pin = GPIO_Pin_6,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
.pin_source = GPIO_PinSource6,
},
.remap = GPIO_AF_TIM8,
},
{
.timer = TIM8,
.timer_chan = TIM_Channel_2,
.pin = {
.gpio = GPIOC,
.init = {
.GPIO_Pin = GPIO_Pin_7,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
.pin_source = GPIO_PinSource7,
},
.remap = GPIO_AF_TIM8,
},
{
.timer = TIM8,
.timer_chan = TIM_Channel_3,
.pin = {
.gpio = GPIOC,
.init = {
.GPIO_Pin = GPIO_Pin_8,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
.pin_source = GPIO_PinSource8,
},
.remap = GPIO_AF_TIM8,
},
{
.timer = TIM8,
.timer_chan = TIM_Channel_4,
.pin = {
.gpio = GPIOC,
.init = {
.GPIO_Pin = GPIO_Pin_9,
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_AF,
.GPIO_OType = GPIO_OType_PP,
.GPIO_PuPd = GPIO_PuPd_UP
},
.pin_source = GPIO_PinSource9,
},
.remap = GPIO_AF_TIM8,
},
};
const struct pios_pwm_cfg pios_pwm_cfg = {
.tim_ic_init = {
.TIM_ICPolarity = TIM_ICPolarity_Rising,
.TIM_ICSelection = TIM_ICSelection_DirectTI,
.TIM_ICPrescaler = TIM_ICPSC_DIV1,
.TIM_ICFilter = 0x0,
},
.channels = pios_tim_rcvrport_all_channels,
.num_channels = NELEMENTS(pios_tim_rcvrport_all_channels),
};
// this configures outputs 2-6 as pwm inputs
const struct pios_pwm_cfg pios_pwm_ppm_cfg = {
.tim_ic_init = {
.TIM_ICPolarity = TIM_ICPolarity_Rising,
.TIM_ICSelection = TIM_ICSelection_DirectTI,
.TIM_ICPrescaler = TIM_ICPSC_DIV1,
.TIM_ICFilter = 0x0,
},
.channels = &pios_tim_rcvrport_all_channels[1],
.num_channels = NELEMENTS(pios_tim_rcvrport_all_channels) - 1,
};
#endif /* if defined(PIOS_INCLUDE_PWM) || defined(PIOS_INCLUDE_PPM) */
/*
* PPM Input
*/
#if defined(PIOS_INCLUDE_PPM)
#include <pios_ppm_priv.h>
static const struct pios_ppm_cfg pios_ppm_cfg = {
.tim_ic_init = {
.TIM_ICPolarity = TIM_ICPolarity_Rising,
.TIM_ICSelection = TIM_ICSelection_DirectTI,
.TIM_ICPrescaler = TIM_ICPSC_DIV1,
.TIM_ICFilter = 0x0,
.TIM_Channel = TIM_Channel_1,
},
/* Use only the first channel for ppm */
.channels = &pios_tim_rcvrport_all_channels[0],
.num_channels = 1,
};
#endif // PPM
#if defined(PIOS_INCLUDE_GCSRCVR)
#include "pios_gcsrcvr_priv.h"
#endif /* PIOS_INCLUDE_GCSRCVR */
#if defined(PIOS_INCLUDE_RCVR)
#include "pios_rcvr_priv.h"
#endif /* PIOS_INCLUDE_RCVR */
#if defined(PIOS_INCLUDE_USB)
#include "pios_usb_priv.h"
static const struct pios_usb_cfg pios_usb_discovery_cfg = {
.irq = {
.init = {
.NVIC_IRQChannel = OTG_FS_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0, // PriorityGroup=4
.NVIC_IRQChannelCmd = ENABLE,
},
},
.vsense = {
.gpio = GPIOA,
.init = {
.GPIO_Pin = GPIO_Pin_9,
.GPIO_Speed = GPIO_Speed_25MHz,
.GPIO_Mode = GPIO_Mode_IN,
.GPIO_OType = GPIO_OType_OD,
},
},
.vsense_active_low = false
};
const struct pios_usb_cfg *PIOS_BOARD_HW_DEFS_GetUsbCfg(__attribute__((unused)) uint32_t board_revision)
{
return &pios_usb_discovery_cfg;
}
#include "pios_usb_board_data_priv.h"
#include "pios_usb_desc_hid_cdc_priv.h"
#include "pios_usb_desc_hid_only_priv.h"
#include "pios_usbhook.h"
#endif /* PIOS_INCLUDE_USB */
#if defined(PIOS_INCLUDE_COM_MSG)
#include <pios_com_msg_priv.h>
#endif /* PIOS_INCLUDE_COM_MSG */
#if defined(PIOS_INCLUDE_USB_HID) && !defined(PIOS_INCLUDE_USB_CDC)
#include <pios_usb_hid_priv.h>
const struct pios_usb_hid_cfg pios_usb_hid_cfg = {
.data_if = 0,
.data_rx_ep = 1,
.data_tx_ep = 1,
};
#endif /* PIOS_INCLUDE_USB_HID && !PIOS_INCLUDE_USB_CDC */
#if defined(PIOS_INCLUDE_USB_HID) && defined(PIOS_INCLUDE_USB_CDC)
#include <pios_usb_cdc_priv.h>
const struct pios_usb_cdc_cfg pios_usb_cdc_cfg = {
.ctrl_if = 0,
.ctrl_tx_ep = 2,
.data_if = 1,
.data_rx_ep = 3,
.data_tx_ep = 3,
};
#include <pios_usb_hid_priv.h>
const struct pios_usb_hid_cfg pios_usb_hid_cfg = {
.data_if = 2,
.data_rx_ep = 1,
.data_tx_ep = 1,
};
#endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_USB_CDC */

View File

@ -0,0 +1,26 @@
#
# Copyright (c) 2009-2013, The OpenPilot Team, http://www.openpilot.org
#
# This program is free software; you can redistribute it and/or modify
# it under the terms of the GNU General Public License as published by
# the Free Software Foundation; either version 3 of the License, or
# (at your option) any later version.
#
# This program is distributed in the hope that it will be useful, but
# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
# for more details.
#
# You should have received a copy of the GNU General Public License along
# with this program; if not, write to the Free Software Foundation, Inc.,
# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
#
ifndef OPENPILOT_IS_COOL
$(error Top level Makefile must be used to build this target)
endif
include ../board-info.mk
include $(ROOT_DIR)/make/firmware-defs.mk
include $(ROOT_DIR)/make/boot-defs.mk
include $(ROOT_DIR)/make/common-defs.mk

View File

@ -0,0 +1,115 @@
/**
******************************************************************************
* @addtogroup CopterControlBL CopterControl BootLoader
* @brief These files contain the code to the CopterControl Bootloader.
*
* @{
* @file common.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief This file contains various common defines for the BootLoader
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef COMMON_H_
#define COMMON_H_
// #include "board.h"
typedef enum {
start, keepgoing,
} DownloadAction;
/**************************************************/
/* OP_DFU states */
/**************************************************/
typedef enum {
DFUidle, // 0
uploading, // 1
wrong_packet_received, // 2
too_many_packets, // 3
too_few_packets, // 4
Last_operation_Success, // 5
downloading, // 6
BLidle, // 7
Last_operation_failed, // 8
uploadingStarting, // 9
outsideDevCapabilities, // 10
CRC_Fail, // 11
failed_jump,
// 12
} DFUStates;
/**************************************************/
/* OP_DFU commands */
/**************************************************/
typedef enum {
Reserved, // 0
Req_Capabilities, // 1
Rep_Capabilities, // 2
EnterDFU, // 3
JumpFW, // 4
Reset, // 5
Abort_Operation, // 6
Upload, // 7
Op_END, // 8
Download_Req, // 9
Download, // 10
Status_Request, // 11
Status_Rep
// 12
} DFUCommands;
typedef enum {
High_Density, Medium_Density
} DeviceType;
/**************************************************/
/* OP_DFU transfer types */
/**************************************************/
typedef enum {
FW, // 0
Descript
// 2
} DFUTransfer;
/**************************************************/
/* OP_DFU transfer port */
/**************************************************/
typedef enum {
Usb, // 0
Serial
// 2
} DFUPort;
/**************************************************/
/* OP_DFU programable programable HW types */
/**************************************************/
typedef enum {
Self_flash, // 0
Remote_flash_via_spi
// 1
} DFUProgType;
/**************************************************/
/* OP_DFU programable sources */
/**************************************************/
#define USB 0
#define SPI 1
#define DownloadDelay 100000
#define MAX_DEL_RETRYS 3
#define MAX_WRI_RETRYS 3
#endif /* COMMON_H_ */

View File

@ -0,0 +1,44 @@
/**
******************************************************************************
*
* @file pios_config.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief PiOS configuration header.
* - Central compile time config for the project.
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PIOS_CONFIG_H
#define PIOS_CONFIG_H
#define PIOS_INCLUDE_DELAY
#define PIOS_INCLUDE_SYS
#define PIOS_INCLUDE_IRQ
#define PIOS_INCLUDE_USB
#define PIOS_INCLUDE_USB_HID
#define PIOS_INCLUDE_LED
#define PIOS_INCLUDE_IAP
#define PIOS_INCLUDE_GPIO
#define PIOS_INCLUDE_COM
#define PIOS_INCLUDE_COM_MSG
#define PIOS_INCLUDE_BL_HELPER
#define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT
#endif /* PIOS_CONFIG_H */

View File

@ -0,0 +1,52 @@
/**
******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_USB_BOARD Board specific USB definitions
* @brief Board specific USB definitions
* @{
*
* @file pios_usb_board_data.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Board specific USB definitions
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PIOS_USB_BOARD_DATA_H
#define PIOS_USB_BOARD_DATA_H
#define PIOS_USB_BOARD_HID_DATA_LENGTH 64
#define PIOS_USB_BOARD_EP_NUM 2
#include <pios_usb_defs.h> /* struct usb_* */
#define PIOS_USB_BOARD_PRODUCT_ID USB_PRODUCT_ID_REVOLUTION
#define PIOS_USB_BOARD_DEVICE_VER USB_OP_DEVICE_VER(USB_OP_BOARD_ID_REVOLUTION, USB_OP_BOARD_MODE_BL)
#define PIOS_USB_BOARD_SN_SUFFIX "+BL"
/*
* The bootloader uses a simplified report structure
* BL: <REPORT_ID><DATA>...<DATA>
* FW: <REPORT_ID><LENGTH><DATA>...<DATA>
* This define changes the behaviour in pios_usb_hid.c
*/
#define PIOS_USB_BOARD_BL_HID_HAS_NO_LENGTH_BYTE
#endif /* PIOS_USB_BOARD_DATA_H */

View File

@ -0,0 +1,252 @@
/**
******************************************************************************
* @addtogroup RevolutionBL Revolution BootLoader
* @brief These files contain the code to the Revolution Bootloader.
*
* @{
* @file main.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief This is the file with the main function of the Revolution BootLoader
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include <pios.h>
#include <pios_board_info.h>
#include <op_dfu.h>
#include <pios_iap.h>
#include <fifo_buffer.h>
#include <pios_com_msg.h>
#include <pios_usbhook.h> /* PIOS_USBHOOK_* */
#include <stdbool.h>
/* Prototype of PIOS_Board_Init() function */
extern void PIOS_Board_Init(void);
extern void FLASH_Download();
void check_bor();
#define BSL_HOLD_STATE ((PIOS_USB_DETECT_GPIO_PORT->IDR & PIOS_USB_DETECT_GPIO_PIN) ? 0 : 1)
/* Private typedef -----------------------------------------------------------*/
typedef void (*pFunction)(void);
/* Private define ------------------------------------------------------------*/
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
pFunction Jump_To_Application;
uint32_t JumpAddress;
/// LEDs PWM
uint32_t period1 = 5000; // 5 mS
uint32_t sweep_steps1 = 100; // * 5 mS -> 500 mS
uint32_t period2 = 5000; // 5 mS
uint32_t sweep_steps2 = 100; // * 5 mS -> 500 mS
////////////////////////////////////////
uint8_t tempcount = 0;
/* Extern variables ----------------------------------------------------------*/
DFUStates DeviceState;
int16_t status = 0;
bool JumpToApp = false;
bool GO_dfu = false;
bool USB_connected = false;
bool User_DFU_request = false;
static uint8_t mReceive_Buffer[63];
/* Private function prototypes -----------------------------------------------*/
uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count);
uint8_t processRX();
void jump_to_app();
int main()
{
PIOS_SYS_Init();
PIOS_Board_Init();
PIOS_IAP_Init();
// Make sure the brown out reset value for this chip
// is 2.7 volts
check_bor();
USB_connected = PIOS_USB_CheckAvailable(0);
if (PIOS_IAP_CheckRequest() == true) {
PIOS_DELAY_WaitmS(1000);
User_DFU_request = true;
PIOS_IAP_ClearRequest();
}
GO_dfu = (USB_connected == true) || (User_DFU_request == true);
if (GO_dfu == true) {
if (User_DFU_request == true) {
DeviceState = DFUidle;
} else {
DeviceState = BLidle;
}
} else {
JumpToApp = true;
}
uint32_t stopwatch = 0;
uint32_t prev_ticks = PIOS_DELAY_GetuS();
while (true) {
/* Update the stopwatch */
uint32_t elapsed_ticks = PIOS_DELAY_GetuSSince(prev_ticks);
prev_ticks += elapsed_ticks;
stopwatch += elapsed_ticks;
if (JumpToApp == true) {
jump_to_app();
}
switch (DeviceState) {
case Last_operation_Success:
case uploadingStarting:
case DFUidle:
period1 = 5000;
sweep_steps1 = 100;
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
period2 = 0;
break;
case uploading:
period1 = 5000;
sweep_steps1 = 100;
period2 = 2500;
sweep_steps2 = 50;
break;
case downloading:
period1 = 2500;
sweep_steps1 = 50;
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
period2 = 0;
break;
case BLidle:
period1 = 0;
PIOS_LED_On(PIOS_LED_HEARTBEAT);
period2 = 0;
break;
default: // error
period1 = 5000;
sweep_steps1 = 100;
period2 = 5000;
sweep_steps2 = 100;
}
if (period1 != 0) {
if (LedPWM(period1, sweep_steps1, stopwatch)) {
PIOS_LED_On(PIOS_LED_HEARTBEAT);
} else {
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
}
} else {
PIOS_LED_On(PIOS_LED_HEARTBEAT);
}
if (period2 != 0) {
if (LedPWM(period2, sweep_steps2, stopwatch)) {
PIOS_LED_On(PIOS_LED_HEARTBEAT);
} else {
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
}
} else {
PIOS_LED_Off(PIOS_LED_HEARTBEAT);
}
if (stopwatch > 50 * 1000 * 1000) {
stopwatch = 0;
}
if ((stopwatch > 6 * 1000 * 1000) && ((DeviceState == BLidle) || (DeviceState == DFUidle && !USB_connected))) {
JumpToApp = true;
}
processRX();
DataDownload(start);
}
}
void jump_to_app()
{
const struct pios_board_info *bdinfo = &pios_board_info_blob;
PIOS_LED_On(PIOS_LED_HEARTBEAT);
// Look at cm3_vectors struct in startup. In a fw image the first uint32_t contains the address of the top of irqstack
uint32_t fwIrqStackBase = (*(__IO uint32_t *)bdinfo->fw_base) & 0xFFFE0000;
// Check for the two possible irqstack locations (sram or core coupled sram)
if (fwIrqStackBase == 0x20000000 || fwIrqStackBase == 0x10000000) {
/* Jump to user application */
FLASH_Lock();
RCC_APB2PeriphResetCmd(0xffffffff, ENABLE);
RCC_APB1PeriphResetCmd(0xffffffff, ENABLE);
RCC_APB2PeriphResetCmd(0xffffffff, DISABLE);
RCC_APB1PeriphResetCmd(0xffffffff, DISABLE);
PIOS_USBHOOK_Deactivate();
JumpAddress = *(__IO uint32_t *)(bdinfo->fw_base + 4);
Jump_To_Application = (pFunction)JumpAddress;
/* Initialize user application's Stack Pointer */
__set_MSP(*(__IO uint32_t *)bdinfo->fw_base);
Jump_To_Application();
} else {
DeviceState = failed_jump;
return;
}
}
uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count)
{
uint32_t curr_step = (count / pwm_period) % pwm_sweep_steps; /* 0 - pwm_sweep_steps */
uint32_t pwm_duty = pwm_period * curr_step / pwm_sweep_steps; /* fraction of pwm_period */
uint32_t curr_sweep = (count / (pwm_period * pwm_sweep_steps)); /* ticks once per full sweep */
if (curr_sweep & 1) {
pwm_duty = pwm_period - pwm_duty; /* reverse direction in odd sweeps */
}
return ((count % pwm_period) > pwm_duty) ? 1 : 0;
}
uint8_t processRX()
{
if (PIOS_COM_MSG_Receive(PIOS_COM_TELEM_USB, mReceive_Buffer, sizeof(mReceive_Buffer))) {
processComand(mReceive_Buffer);
}
return true;
}
/**
* Check the brown out reset threshold is 2.7 volts and if not
* resets it. This solves an issue that can prevent boards
* powering up with some BEC
*/
void check_bor()
{
uint8_t bor = FLASH_OB_GetBOR();
if (bor != OB_BOR_LEVEL3) {
FLASH_OB_Unlock();
FLASH_OB_BORConfig(OB_BOR_LEVEL3);
FLASH_OB_Launch();
while (FLASH_WaitForLastOperation() == FLASH_BUSY) {
;
}
FLASH_OB_Lock();
while (FLASH_WaitForLastOperation() == FLASH_BUSY) {
;
}
}
}

View File

@ -0,0 +1,84 @@
/**
******************************************************************************
*
* @file pios_board.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Defines board specific static initializers for hardware for the AHRS board.
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include <pios.h>
#include <pios_board_info.h>
/*
* Pull in the board-specific static HW definitions.
* Including .c files is a bit ugly but this allows all of
* the HW definitions to be const and static to limit their
* scope.
*
* NOTE: THIS IS THE ONLY PLACE THAT SHOULD EVER INCLUDE THIS FILE
*/
#include "../board_hw_defs.c"
uint32_t pios_com_telem_usb_id;
static bool board_init_complete = false;
void PIOS_Board_Init()
{
if (board_init_complete) {
return;
}
/* Delay system */
PIOS_DELAY_Init();
const struct pios_board_info *bdinfo = &pios_board_info_blob;
#if defined(PIOS_INCLUDE_LED)
const struct pios_gpio_cfg *led_cfg = PIOS_BOARD_HW_DEFS_GetLedCfg(bdinfo->board_rev);
PIOS_Assert(led_cfg);
PIOS_LED_Init(led_cfg);
#endif /* PIOS_INCLUDE_LED */
#if defined(PIOS_INCLUDE_USB)
/* Initialize board specific USB data */
PIOS_USB_BOARD_DATA_Init();
/* Activate the HID-only USB configuration */
PIOS_USB_DESC_HID_ONLY_Init();
uint32_t pios_usb_id;
PIOS_USB_Init(&pios_usb_id, PIOS_BOARD_HW_DEFS_GetUsbCfg(bdinfo->board_rev));
#if defined(PIOS_INCLUDE_USB_HID) && defined(PIOS_INCLUDE_COM_MSG)
uint32_t pios_usb_hid_id;
if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) {
PIOS_Assert(0);
}
if (PIOS_COM_MSG_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id)) {
PIOS_Assert(0);
}
#endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_COM_MSG */
PIOS_USBHOOK_Activate();
#endif /* PIOS_INCLUDE_USB */
board_init_complete = true;
}

View File

@ -0,0 +1,100 @@
#
# Copyright (c) 2009-2013, The OpenPilot Team, http://www.openpilot.org
# Copyright (c) 2012, PhoenixPilot, http://github.com/PhoenixPilot
#
# This program is free software; you can redistribute it and/or modify
# it under the terms of the GNU General Public License as published by
# the Free Software Foundation; either version 3 of the License, or
# (at your option) any later version.
#
# This program is distributed in the hope that it will be useful, but
# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
# for more details.
#
# You should have received a copy of the GNU General Public License along
# with this program; if not, write to the Free Software Foundation, Inc.,
# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
#####
ifndef OPENPILOT_IS_COOL
$(error Top level Makefile must be used to build this target)
endif
include ../board-info.mk
include $(ROOT_DIR)/make/firmware-defs.mk
# ARM DSP library
USE_DSP_LIB ?= NO
# List of mandatory modules to include
#MODULES += Sensors
#MODULES += Attitude/revolution
#MODULES += StateEstimation # use instead of Attitude
#MODULES += Altitude/revolution
#MODULES += Airspeed
#MODULES += AltitudeHold
#MODULES += Stabilization
MODULES += VtolPathFollower
MODULES += ManualControl
MODULES += Actuator
MODULES += GPS
MODULES += TxPID
MODULES += CameraStab
MODULES += Battery
MODULES += FirmwareIAP
#MODULES += Radio
MODULES += PathPlanner
MODULES += FixedWingPathFollower
MODULES += Osd/osdoutout
MODULES += Logging
MODULES += Telemetry
OPTMODULES += ComUsbBridge
# Include all camera options
CDEFS += -DUSE_INPUT_LPF -DUSE_GIMBAL_LPF -DUSE_GIMBAL_FF
# Some diagnostics
CDEFS += -DDIAG_TASKS
# Misc options
CFLAGS += -ffast-math
# List C source files here (C dependencies are automatically generated).
# Use file-extension c for "c-only"-files
ifndef TESTAPP
## Application Core
SRC += ../pios_usb_board_data.c
SRC += $(OPMODULEDIR)/System/systemmod.c
SRC += $(OPSYSTEM)/discoveryf4bare.c
SRC += $(OPSYSTEM)/pios_board.c
SRC += $(FLIGHTLIB)/alarms.c
SRC += $(OPUAVTALK)/uavtalk.c
SRC += $(OPUAVOBJ)/uavobjectmanager.c
SRC += $(OPUAVOBJ)/eventdispatcher.c
#ifeq ($(DEBUG), YES)
SRC += $(OPSYSTEM)/dcc_stdio.c
SRC += $(OPSYSTEM)/cm3_fault_handlers.c
#endif
## Misc library functions
SRC += $(FLIGHTLIB)/paths.c
SRC += $(FLIGHTLIB)/WorldMagModel.c
SRC += $(FLIGHTLIB)/insgps13state.c
## UAVObjects
include ./UAVObjects.inc
SRC += $(UAVOBJSRC)
else
## Test Code
SRC += $(OPTESTS)/test_common.c
SRC += $(OPTESTS)/$(TESTAPP).c
endif
# Optional component libraries
include $(FLIGHTLIB)/rscode/library.mk
#include $(FLIGHTLIB)/PyMite/pymite.mk
include $(ROOT_DIR)/make/apps-defs.mk
include $(ROOT_DIR)/make/common-defs.mk

View File

@ -0,0 +1,118 @@
#
# Copyright (c) 2009-2013, The OpenPilot Team, http://www.openpilot.org
#
# This program is free software; you can redistribute it and/or modify
# it under the terms of the GNU General Public License as published by
# the Free Software Foundation; either version 3 of the License, or
# (at your option) any later version.
#
# This program is distributed in the hope that it will be useful, but
# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
# for more details.
#
# You should have received a copy of the GNU General Public License along
# with this program; if not, write to the Free Software Foundation, Inc.,
# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
#
# These are the UAVObjects supposed to be build as part of the OpenPilot target
# (all architectures)
UAVOBJSRCFILENAMES =
UAVOBJSRCFILENAMES += accelgyrosettings
UAVOBJSRCFILENAMES += accessorydesired
UAVOBJSRCFILENAMES += actuatorcommand
UAVOBJSRCFILENAMES += actuatordesired
UAVOBJSRCFILENAMES += actuatorsettings
UAVOBJSRCFILENAMES += attitudesettings
UAVOBJSRCFILENAMES += attitudestate
UAVOBJSRCFILENAMES += gyrostate
UAVOBJSRCFILENAMES += gyrosensor
UAVOBJSRCFILENAMES += accelstate
UAVOBJSRCFILENAMES += accelsensor
UAVOBJSRCFILENAMES += magsensor
UAVOBJSRCFILENAMES += magstate
UAVOBJSRCFILENAMES += barosensor
UAVOBJSRCFILENAMES += airspeedsensor
UAVOBJSRCFILENAMES += airspeedsettings
UAVOBJSRCFILENAMES += airspeedstate
UAVOBJSRCFILENAMES += debuglogsettings
UAVOBJSRCFILENAMES += debuglogcontrol
UAVOBJSRCFILENAMES += debuglogstatus
UAVOBJSRCFILENAMES += debuglogentry
UAVOBJSRCFILENAMES += flightbatterysettings
UAVOBJSRCFILENAMES += firmwareiapobj
UAVOBJSRCFILENAMES += flightbatterystate
UAVOBJSRCFILENAMES += flightplancontrol
UAVOBJSRCFILENAMES += flightplansettings
UAVOBJSRCFILENAMES += flightplanstatus
UAVOBJSRCFILENAMES += flighttelemetrystats
UAVOBJSRCFILENAMES += gcstelemetrystats
UAVOBJSRCFILENAMES += gcsreceiver
UAVOBJSRCFILENAMES += gpspositionsensor
UAVOBJSRCFILENAMES += gpssatellites
UAVOBJSRCFILENAMES += gpstime
UAVOBJSRCFILENAMES += gpsvelocitysensor
UAVOBJSRCFILENAMES += gpssettings
UAVOBJSRCFILENAMES += fixedwingpathfollowersettings
UAVOBJSRCFILENAMES += fixedwingpathfollowerstatus
UAVOBJSRCFILENAMES += vtolpathfollowersettings
UAVOBJSRCFILENAMES += homelocation
UAVOBJSRCFILENAMES += i2cstats
UAVOBJSRCFILENAMES += manualcontrolcommand
UAVOBJSRCFILENAMES += manualcontrolsettings
UAVOBJSRCFILENAMES += flightmodesettings
UAVOBJSRCFILENAMES += mixersettings
UAVOBJSRCFILENAMES += mixerstatus
UAVOBJSRCFILENAMES += nedaccel
UAVOBJSRCFILENAMES += objectpersistence
UAVOBJSRCFILENAMES += oplinkreceiver
UAVOBJSRCFILENAMES += overosyncstats
UAVOBJSRCFILENAMES += overosyncsettings
UAVOBJSRCFILENAMES += pathaction
UAVOBJSRCFILENAMES += pathdesired
UAVOBJSRCFILENAMES += pathplan
UAVOBJSRCFILENAMES += pathstatus
UAVOBJSRCFILENAMES += positionstate
UAVOBJSRCFILENAMES += ratedesired
UAVOBJSRCFILENAMES += relaytuning
UAVOBJSRCFILENAMES += relaytuningsettings
UAVOBJSRCFILENAMES += ekfconfiguration
UAVOBJSRCFILENAMES += ekfstatevariance
UAVOBJSRCFILENAMES += revocalibration
UAVOBJSRCFILENAMES += revosettings
UAVOBJSRCFILENAMES += sonaraltitude
UAVOBJSRCFILENAMES += stabilizationdesired
UAVOBJSRCFILENAMES += stabilizationsettings
UAVOBJSRCFILENAMES += stabilizationsettingsbank1
UAVOBJSRCFILENAMES += stabilizationsettingsbank2
UAVOBJSRCFILENAMES += stabilizationsettingsbank3
UAVOBJSRCFILENAMES += stabilizationstatus
UAVOBJSRCFILENAMES += stabilizationbank
UAVOBJSRCFILENAMES += systemalarms
UAVOBJSRCFILENAMES += systemsettings
UAVOBJSRCFILENAMES += systemstats
UAVOBJSRCFILENAMES += taskinfo
UAVOBJSRCFILENAMES += callbackinfo
UAVOBJSRCFILENAMES += velocitystate
UAVOBJSRCFILENAMES += velocitydesired
UAVOBJSRCFILENAMES += watchdogstatus
UAVOBJSRCFILENAMES += flightstatus
UAVOBJSRCFILENAMES += hwsettings
UAVOBJSRCFILENAMES += receiveractivity
UAVOBJSRCFILENAMES += cameradesired
UAVOBJSRCFILENAMES += camerastabsettings
UAVOBJSRCFILENAMES += altitudeholdsettings
UAVOBJSRCFILENAMES += oplinksettings
UAVOBJSRCFILENAMES += oplinkstatus
UAVOBJSRCFILENAMES += altitudefiltersettings
UAVOBJSRCFILENAMES += altitudeholdstatus
UAVOBJSRCFILENAMES += waypoint
UAVOBJSRCFILENAMES += waypointactive
UAVOBJSRCFILENAMES += poilocation
UAVOBJSRCFILENAMES += poilearnsettings
UAVOBJSRCFILENAMES += mpu6000settings
UAVOBJSRCFILENAMES += txpidsettings
UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(OPUAVSYNTHDIR)/$(UAVOBJSRCFILE).c )
UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) )

View File

@ -0,0 +1,90 @@
/*
* cm3_fault_handlers.c
*
* Created on: Apr 24, 2011
* Author: msmith
*/
#include <stdint.h>
#include "inc/dcc_stdio.h"
#ifdef STM32F4XX
# include <stm32f4xx.h>
#endif
#ifdef STM32F2XX
# include <stm32f2xx.h>
#endif
#define FAULT_TRAMPOLINE(_vec) \
__attribute__((naked, no_instrument_function)) \
void \
_vec##_Handler(void) \
{ \
__asm(".syntax unified\n" \
"MOVS R0, #4 \n" \
"MOV R1, LR \n" \
"TST R0, R1 \n" \
"BEQ 1f \n" \
"MRS R0, PSP \n" \
"B " #_vec "_Handler2 \n" \
"1: \n" \
"MRS R0, MSP \n" \
"B " #_vec "_Handler2 \n" \
".syntax divided\n"); \
} \
struct hack
struct cm3_frame {
uint32_t r0;
uint32_t r1;
uint32_t r2;
uint32_t r3;
uint32_t r12;
uint32_t lr;
uint32_t pc;
uint32_t psr;
};
FAULT_TRAMPOLINE(HardFault);
FAULT_TRAMPOLINE(BusFault);
FAULT_TRAMPOLINE(UsageFault);
/* this is a hackaround to avoid an issue where dereferencing SCB seems to result in bad codegen and a link error */
#define SCB_REG(_reg) (*(uint32_t *)&(SCB->_reg))
void HardFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nHARD FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(HFSR));
dbg_write_char('\n');
for (;;) {
;
}
}
void BusFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nBUS FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(CFSR));
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(BFAR));
dbg_write_char('\n');
for (;;) {
;
}
}
void UsageFault_Handler2(struct cm3_frame *frame)
{
dbg_write_str("\nUSAGE FAULT");
dbg_write_hex32(frame->pc);
dbg_write_char('\n');
dbg_write_hex32(SCB_REG(CFSR));
dbg_write_char('\n');
for (;;) {
;
}
}

View File

@ -0,0 +1,149 @@
/***************************************************************************
* Copyright (C) 2008 by Dominic Rath *
* Dominic.Rath@gmx.de *
* Copyright (C) 2008 by Spencer Oliver *
* spen@spen-soft.co.uk *
* Copyright (C) 2008 by Frederik Kriewtz *
* frederik@kriewitz.eu *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License, or *
* (at your option) any later version. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#include "inc/dcc_stdio.h"
#define TARGET_REQ_TRACEMSG 0x00
#define TARGET_REQ_DEBUGMSG_ASCII 0x01
#define TARGET_REQ_DEBUGMSG_HEXMSG(size) (0x01 | ((size & 0xff) << 8))
#define TARGET_REQ_DEBUGCHAR 0x02
/* we use the cortex_m3 DCRDR reg to simulate a arm7_9 dcc channel
* DCRDR[7:0] is used by target for status
* DCRDR[15:8] is used by target for write buffer
* DCRDR[23:16] is used for by host for status
* DCRDR[31:24] is used for by host for write buffer */
#define NVIC_DBG_DATA_R (*((volatile unsigned short *)0xE000EDF8))
#define BUSY 1
void dbg_write(unsigned long dcc_data)
{
int len = 4;
while (len--) {
/* wait for data ready */
while (NVIC_DBG_DATA_R & BUSY) {
;
}
/* write our data and set write flag - tell host there is data*/
NVIC_DBG_DATA_R = (unsigned short)(((dcc_data & 0xff) << 8) | BUSY);
dcc_data >>= 8;
}
}
void dbg_trace_point(unsigned long number)
{
dbg_write(TARGET_REQ_TRACEMSG | (number << 8));
}
void dbg_write_u32(const unsigned long *val, long len)
{
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(4) | ((len & 0xffff) << 16));
while (len > 0) {
dbg_write(*val);
val++;
len--;
}
}
void dbg_write_u16(const unsigned short *val, long len)
{
unsigned long dcc_data;
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(2) | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = val[0]
| ((len > 1) ? val[1] << 16 : 0x0000);
dbg_write(dcc_data);
val += 2;
len -= 2;
}
}
void dbg_write_u8(const unsigned char *val, long len)
{
unsigned long dcc_data;
dbg_write(TARGET_REQ_DEBUGMSG_HEXMSG(1) | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = val[0]
| ((len > 1) ? val[1] << 8 : 0x00)
| ((len > 2) ? val[2] << 16 : 0x00)
| ((len > 3) ? val[3] << 24 : 0x00);
dbg_write(dcc_data);
val += 4;
len -= 4;
}
}
void dbg_write_str(const char *msg)
{
long len;
unsigned long dcc_data;
for (len = 0; msg[len] && (len < 65536); len++) {
;
}
dbg_write(TARGET_REQ_DEBUGMSG_ASCII | ((len & 0xffff) << 16));
while (len > 0) {
dcc_data = msg[0]
| ((len > 1) ? msg[1] << 8 : 0x00)
| ((len > 2) ? msg[2] << 16 : 0x00)
| ((len > 3) ? msg[3] << 24 : 0x00);
dbg_write(dcc_data);
msg += 4;
len -= 4;
}
}
void dbg_write_char(char msg)
{
dbg_write(TARGET_REQ_DEBUGCHAR | ((msg & 0xff) << 16));
}
void dbg_write_hex32(const unsigned long val)
{
static const char hextab[] = {
'0', '1', '2', '3', '4', '5', '6', '7',
'8', '9', 'a', 'b', 'c', 'd', 'e', 'f'
};
for (int shift = 28; shift >= 0; shift -= 4) {
dbg_write_char(hextab[(val >> shift) & 0xf]);
}
}

View File

@ -0,0 +1,139 @@
/**
******************************************************************************
* @addtogroup OpenPilotSystem OpenPilot System
* @brief These files are the core system files of OpenPilot.
* They are the ground layer just above PiOS. In practice, OpenPilot actually starts
* in the main() function of openpilot.c
* @{
* @addtogroup OpenPilotCore OpenPilot Core
* @brief This is where the OP firmware starts. Those files also define the compile-time
* options of the firmware.
* @{
* @file openpilot.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Sets up and runs main OpenPilot tasks.
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "inc/openpilot.h"
#include <uavobjectsinit.h>
/* Task Priorities */
#define PRIORITY_TASK_HOOKS (tskIDLE_PRIORITY + 3)
/* Global Variables */
/* Local Variables */
#define INCLUDE_TEST_TASKS 0
#if INCLUDE_TEST_TASKS
static uint8_t sdcard_available;
#endif
char Buffer[1024];
uint32_t Cache;
/* Function Prototypes */
#if INCLUDE_TEST_TASKS
static void TaskTick(void *pvParameters);
static void TaskTesting(void *pvParameters);
static void TaskHIDTest(void *pvParameters);
static void TaskServos(void *pvParameters);
static void TaskSDCard(void *pvParameters);
#endif
int32_t CONSOLE_Parse(uint8_t port, char c);
void OP_ADC_NotifyChange(uint32_t pin, uint32_t pin_value);
/* Prototype of PIOS_Board_Init() function */
extern void PIOS_Board_Init(void);
extern void Stack_Change(void);
static void Stack_Change_Weak() __attribute__((weakref("Stack_Change")));
/* Local Variables */
#define INIT_TASK_PRIORITY (tskIDLE_PRIORITY + configMAX_PRIORITIES - 1) // max priority
#define INIT_TASK_STACK (1024 / 4) // XXX this seems excessive
static xTaskHandle initTaskHandle;
/* Function Prototypes */
static void initTask(void *parameters);
/* Prototype of generated InitModules() function */
extern void InitModules(void);
/**
* OpenPilot Main function:
*
* Initialize PiOS<BR>
* Create the "System" task (SystemModInitializein Modules/System/systemmod.c) <BR>
* Start FreeRTOS Scheduler (vTaskStartScheduler)<BR>
* If something goes wrong, blink LED1 and LED2 every 100ms
*
*/
int main()
{
int result;
/* NOTE: Do NOT modify the following start-up sequence */
/* Any new initialization functions should be added in OpenPilotInit() */
vPortInitialiseBlocks();
/* Brings up System using CMSIS functions, enables the LEDs. */
PIOS_SYS_Init();
/* For Revolution we use a FreeRTOS task to bring up the system so we can */
/* always rely on FreeRTOS primitive */
result = xTaskCreate(initTask, (const signed char *)"init",
INIT_TASK_STACK, NULL, INIT_TASK_PRIORITY,
&initTaskHandle);
PIOS_Assert(result == pdPASS);
/* Start the FreeRTOS scheduler */
vTaskStartScheduler();
/* If all is well we will never reach here as the scheduler will now be running. */
/* Do some PIOS_LED_HEARTBEAT to user that something bad just happened */
PIOS_LED_Off(PIOS_LED_HEARTBEAT); \
for (;;) { \
PIOS_LED_Toggle(PIOS_LED_HEARTBEAT); \
PIOS_DELAY_WaitmS(100); \
}
;
return 0;
}
/**
* Initialisation task.
*
* Runs board and module initialisation, then terminates.
*/
void initTask(__attribute__((unused)) void *parameters)
{
/* board driver init */
PIOS_Board_Init();
/* Initialize modules */
MODULE_INITIALISE_ALL;
/* terminate this task */
vTaskDelete(NULL);
}
/**
* @}
* @}
*/

View File

@ -0,0 +1,105 @@
#ifndef FREERTOS_CONFIG_H
#define FREERTOS_CONFIG_H
/*-----------------------------------------------------------
* Application specific definitions.
*
* These definitions should be adjusted for your particular hardware and
* application requirements.
*
* THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE
* FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE.
*
* See http://www.freertos.org/a00110.html.
*----------------------------------------------------------*/
/**
* @addtogroup PIOS PIOS
* @{
* @addtogroup FreeRTOS FreeRTOS
* @{
*/
/* Notes: We use 5 task priorities */
#define configCPU_CLOCK_HZ (SYSCLK_FREQ) // really the NVIC clock ...
#define configTICK_RATE_HZ ((portTickType)1000)
#define configMAX_PRIORITIES ((unsigned portBASE_TYPE)5)
#define configMINIMAL_STACK_SIZE ((unsigned short)512)
#define configTOTAL_HEAP_SIZE ((size_t)(180 * 1024)) // this is minimum, not total
#define configMAX_TASK_NAME_LEN (16)
#define configUSE_PREEMPTION 1
#define configUSE_IDLE_HOOK 1
#define configUSE_TICK_HOOK 0
#define configUSE_TRACE_FACILITY 0
#define configUSE_16_BIT_TICKS 0
#define configIDLE_SHOULD_YIELD 0
#define configUSE_MUTEXES 1
#define configUSE_RECURSIVE_MUTEXES 1
#define configUSE_COUNTING_SEMAPHORES 0
#define configUSE_ALTERNATIVE_API 0
#define configCHECK_FOR_STACK_OVERFLOW 2
#define configQUEUE_REGISTRY_SIZE 10
#define configUSE_TIMERS 1
#define configTIMER_TASK_PRIORITY (configMAX_PRIORITIES - 1) /* run timers at max priority */
#define configTIMER_QUEUE_LENGTH 10
#define configTIMER_TASK_STACK_DEPTH configMINIMAL_STACK_SIZE
/* Co-routine definitions. */
#define configUSE_CO_ROUTINES 0
#define configMAX_CO_ROUTINE_PRIORITIES (2)
/* Set the following definitions to 1 to include the API function, or zero
to exclude the API function. */
#define INCLUDE_vTaskPrioritySet 1
#define INCLUDE_uxTaskPriorityGet 1
#define INCLUDE_vTaskDelete 1
#define INCLUDE_vTaskCleanUpResources 1
#define INCLUDE_vTaskSuspend 1
#define INCLUDE_vTaskDelayUntil 1
#define INCLUDE_vTaskDelay 1
#define INCLUDE_xTaskGetSchedulerState 1
#define INCLUDE_xTaskGetCurrentTaskHandle 1
#define INCLUDE_uxTaskGetStackHighWaterMark 1
#define INCLUDE_xTaskGetIdleTaskHandle 1
/* This is the raw value as per the Cortex-M3 NVIC. Values can be 255
(lowest) to 1 (highest maskable) to 0 (highest non-maskable). */
#define configKERNEL_INTERRUPT_PRIORITY 15 << 4 /* equivalent to NVIC priority 15 */
#define configMAX_SYSCALL_INTERRUPT_PRIORITY 3 << 4 /* equivalent to NVIC priority 3 */
/* This is the value being used as per the ST library which permits 16
priority values, 0 to 15. This must correspond to the
configKERNEL_INTERRUPT_PRIORITY setting. Here 15 corresponds to the lowest
NVIC value of 255. */
#define configLIBRARY_KERNEL_INTERRUPT_PRIORITY 15
/* Enable run time stats collection */
#define configGENERATE_RUN_TIME_STATS 1
#define INCLUDE_uxTaskGetRunTime 1
/*
* Once we move to CMSIS2 we can at least use:
*
* CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk;
*
* (still nothing for the DWT registers, surprisingly)
*/
#define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() \
do { \
(*(unsigned long *)0xe000edfc) |= (1 << 24); /* DEMCR |= DEMCR_TRCENA */ \
(*(unsigned long *)0xe0001000) |= 1; /* DWT_CTRL |= DWT_CYCCNT_ENA */ \
} \
while (0)
#define portGET_RUN_TIME_COUNTER_VALUE() (*(unsigned long *)0xe0001004) /* DWT_CYCCNT */
/**
* @}
*/
#endif /* FREERTOS_CONFIG_H */

View File

@ -0,0 +1,36 @@
/***************************************************************************
* Copyright (C) 2008 by Dominic Rath *
* Dominic.Rath@gmx.de *
* Copyright (C) 2008 by Spencer Oliver *
* spen@spen-soft.co.uk *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License, or *
* (at your option) any later version. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
***************************************************************************/
#ifndef DCC_STDIO_H
#define DCC_STDIO_H
void dbg_trace_point(unsigned long number);
void dbg_write_u32(const unsigned long *val, long len);
void dbg_write_u16(const unsigned short *val, long len);
void dbg_write_u8(const unsigned char *val, long len);
void dbg_write_str(const char *msg);
void dbg_write_char(char msg);
void dbg_write_hex32(const unsigned long val);
#endif /* DCC_STDIO_H */

View File

@ -0,0 +1,52 @@
/**
******************************************************************************
* @addtogroup OpenPilotSystem OpenPilot System
* @{
* @addtogroup OpenPilotCore OpenPilot Core
* @{
* @file openpilot.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Main OpenPilot header.
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef OPENPILOT_H
#define OPENPILOT_H
/* PIOS Includes */
#include <pios.h>
/* OpenPilot Libraries */
#include <utlist.h>
#include <uavobjectmanager.h>
#include <eventdispatcher.h>
#include <uavtalk.h>
#include "alarms.h"
#include <mathmisc.h>
/* Global Functions */
void OpenPilotInit(void);
#endif /* OPENPILOT_H */
/**
* @}
* @}
*/

View File

@ -0,0 +1,82 @@
/**
******************************************************************************
*
* @file pios_board.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Defines board hardware for the OpenPilot Version 1.1 hardware.
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PIOS_BOARD_H
#define PIOS_BOARD_H
// ------------------------
// PIOS_LED
// ------------------------
#define PIOS_LED_ALARM 0
#define PIOS_LED_HEARTBEAT 1
#define PIOS_LED_NUM 2
// -------------------------
// COM
//
// See also pios_board_posix.c
// -------------------------
// #define PIOS_USART_TX_BUFFER_SIZE 256
#define PIOS_COM_BUFFER_SIZE 1024
#define PIOS_COM_MAX_DEVS 255
#define PIOS_UDP_RX_BUFFER_SIZE PIOS_COM_BUFFER_SIZE
#define PIOS_TCP_RX_BUFFER_SIZE PIOS_COM_BUFFER_SIZE
extern uint32_t pios_com_telem_rf_id;
extern uint32_t pios_com_telem_usb_id;
extern uint32_t pios_com_gps_id;
extern uint32_t pios_com_aux_id;
extern uint32_t pios_com_spectrum_id;
#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id)
#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id)
#define PIOS_COM_GPS (pios_com_gps_id)
#ifdef PIOS_ENABLE_AUX_UART
#define PIOS_COM_AUX (pios_com_aux_id)
#define PIOS_COM_DEBUG (PIOS_COM_AUX)
#endif
#define PIOS_GCSRCVR_TIMEOUT_MS 200
/**
* glue macros for file IO
* STM32 uses DOSFS for file IO
*/
#define PIOS_FOPEN_READ(filename, file) (file = fopen((char *)filename, "r")) == NULL
#define PIOS_FOPEN_WRITE(filename, file) (file = fopen((char *)filename, "w")) == NULL
#define PIOS_FREAD(file, bufferadr, length, resultadr) (*resultadr = fread((uint8_t *)bufferadr, 1, length, *file)) != length
#define PIOS_FWRITE(file, bufferadr, length, resultadr) *resultadr = fwrite((uint8_t *)bufferadr, 1, length, *file)
#define PIOS_FCLOSE(file) fclose(file)
#define PIOS_FUNLINK(file) unlink((char *)filename)
#endif /* PIOS_BOARD_H */

View File

@ -0,0 +1,178 @@
/**
******************************************************************************
* @addtogroup OpenPilotSystem OpenPilot System
* @{
* @addtogroup OpenPilotCore OpenPilot Core
* @{
* @file pios_config.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2013.
* @brief PiOS configuration header, the compile time config file for the PIOS.
* Defines which PiOS libraries and features are included in the firmware.
* @see The GNU Public License (GPL) Version 3
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PIOS_CONFIG_H
#define PIOS_CONFIG_H
/*
* Below is a complete list of PIOS configurable options.
* Please do not remove or rearrange them. Only comment out
* unused options in the list. See main pios.h header for more
* details.
*/
/* #define PIOS_INCLUDE_DEBUG_CONSOLE */
/* #define DEBUG_LEVEL 0 */
/* #define PIOS_ENABLE_DEBUG_PINS */
/* PIOS FreeRTOS support */
#define PIOS_INCLUDE_FREERTOS
/* PIOS Callback Scheduler support */
#define PIOS_INCLUDE_CALLBACKSCHEDULER
/* PIOS bootloader helper */
#define PIOS_INCLUDE_BL_HELPER
/* #define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT */
/* PIOS system functions */
#define PIOS_INCLUDE_DELAY
#define PIOS_INCLUDE_INITCALL
#define PIOS_INCLUDE_SYS
#define PIOS_INCLUDE_TASK_MONITOR
/* PIOS hardware peripherals */
#define PIOS_INCLUDE_IRQ
#define PIOS_INCLUDE_RTC
#define PIOS_INCLUDE_TIM
#define PIOS_INCLUDE_USART
#define PIOS_INCLUDE_ADC
#define PIOS_INCLUDE_I2C
#define PIOS_INCLUDE_SPI
#define PIOS_INCLUDE_GPIO
#define PIOS_INCLUDE_EXTI
#define PIOS_INCLUDE_WDG
/* PIOS USB functions */
#define PIOS_INCLUDE_USB
#define PIOS_INCLUDE_USB_HID
#define PIOS_INCLUDE_USB_CDC
/* #define PIOS_INCLUDE_USB_RCTX */
/* PIOS sensor interfaces */
/* #define PIOS_INCLUDE_ADXL345 */
/* #define PIOS_INCLUDE_BMA180 */
/* #define PIOS_INCLUDE_L3GD20 */
//#define PIOS_INCLUDE_MPU6000
//#define PIOS_MPU6000_ACCEL
/* #define PIOS_INCLUDE_HMC5843 */
//#define PIOS_INCLUDE_HMC5883
//#define PIOS_HMC5883_HAS_GPIOS
/* #define PIOS_INCLUDE_BMP085 */
//#define PIOS_INCLUDE_MS5611
//#define PIOS_INCLUDE_MPXV
//#define PIOS_INCLUDE_ETASV3
/* #define PIOS_INCLUDE_HCSR04 */
/* PIOS receiver drivers */
#define PIOS_INCLUDE_PWM
#define PIOS_INCLUDE_PPM
/* #define PIOS_INCLUDE_PPM_FLEXI */
#define PIOS_INCLUDE_DSM
#define PIOS_INCLUDE_SBUS
#define PIOS_INCLUDE_GCSRCVR
//#define PIOS_INCLUDE_OPLINKRCVR
/* PIOS abstract receiver interface */
#define PIOS_INCLUDE_RCVR
/* PIOS common peripherals */
#define PIOS_INCLUDE_LED
#define PIOS_INCLUDE_IAP
#define PIOS_INCLUDE_SERVO
/* #define PIOS_INCLUDE_I2C_ESC */
/* #define PIOS_INCLUDE_OVERO */
/* #define PIOS_OVERO_SPI */
/* #define PIOS_INCLUDE_SDCARD */
/* #define LOG_FILENAME "startup.log" */
#define PIOS_INCLUDE_FLASH
#define PIOS_INCLUDE_FLASH_INTERNAL
#define PIOS_INCLUDE_FLASH_LOGFS_SETTINGS
#define FLASH_FREERTOS
/* #define PIOS_INCLUDE_FLASH_EEPROM */
/* PIOS radio modules */
//#define PIOS_INCLUDE_RFM22B
//#define PIOS_INCLUDE_RFM22B_COM
//#define PIOS_INCLUDE_RFM22B_RCVR
/* #define PIOS_INCLUDE_PPM_OUT */
/* #define PIOS_RFM22B_DEBUG_ON_TELEM */
/* PIOS misc peripherals */
/* #define PIOS_INCLUDE_VIDEO */
/* #define PIOS_INCLUDE_WAVE */
/* #define PIOS_INCLUDE_UDP */
/* PIOS abstract comms interface with options */
#define PIOS_INCLUDE_COM
/* #define PIOS_INCLUDE_COM_MSG */
/* #define PIOS_INCLUDE_TELEMETRY_RF */
#define PIOS_INCLUDE_COM_TELEM
#define PIOS_INCLUDE_COM_FLEXI
/* #define PIOS_INCLUDE_COM_AUX */
#define PIOS_TELEM_PRIORITY_QUEUE
#define PIOS_INCLUDE_GPS
/* #define PIOS_GPS_MINIMAL */
#define PIOS_INCLUDE_GPS_NMEA_PARSER
#define PIOS_INCLUDE_GPS_UBX_PARSER
#define PIOS_GPS_SETS_HOMELOCATION
/* Stabilization options */
/* #define PIOS_QUATERNION_STABILIZATION */
/* Performance counters */
#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD 8379692
/* Alarm Thresholds */
#define HEAP_LIMIT_WARNING 1000
#define HEAP_LIMIT_CRITICAL 500
#define IRQSTACK_LIMIT_WARNING 150
#define IRQSTACK_LIMIT_CRITICAL 80
#define CPULOAD_LIMIT_WARNING 80
#define CPULOAD_LIMIT_CRITICAL 95
/* Task stack sizes */
/* #define PIOS_ACTUATOR_STACK_SIZE 1020 */
/* #define PIOS_MANUAL_STACK_SIZE 800 */
/* #define PIOS_SYSTEM_STACK_SIZE 660 */
/* #define PIOS_STABILIZATION_STACK_SIZE 524 */
/* #define PIOS_TELEM_STACK_SIZE 500 */
/* #define PIOS_EVENTDISPATCHER_STACK_SIZE 130 */
/* This can't be too high to stop eventdispatcher thread overflowing */
#define PIOS_EVENTDISAPTCHER_QUEUE 10
/* Revolution series */
#define REVOLUTION
#endif /* PIOS_CONFIG_H */
/**
* @}
* @}
*/

View File

@ -0,0 +1,80 @@
/**
******************************************************************************
*
* @file pios_config.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief PiOS configuration header.
* Central compile time config for the project.
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PIOS_CONFIG_POSIX_H
#define PIOS_CONFIG_POSIX_H
/* Enable/Disable PiOS Modules */
#define PIOS_INCLUDE_SYS
#define PIOS_INCLUDE_DELAY
#define PIOS_INCLUDE_LED
#define PIOS_INCLUDE_SDCARD
#define PIOS_INCLUDE_FREERTOS
#define PIOS_INCLUDE_TASK_MONITOR
#define PIOS_INCLUDE_COM
// #define PIOS_INCLUDE_GPS
#define PIOS_INCLUDE_IRQ
#define PIOS_INCLUDE_TELEMETRY_RF
#define PIOS_INCLUDE_TCP
#define PIOS_INCLUDE_UDP
#define PIOS_INCLUDE_SERVO
#define PIOS_INCLUDE_RCVR
#define PIOS_INCLUDE_GCSRCVR
#define PIOS_RCVR_MAX_CHANNELS 12
#define PIOS_RCVR_MAX_DEVS 3
/* Defaults for Logging */
#define LOG_FILENAME "PIOS.LOG"
#define STARTUP_LOG_ENABLED 1
/* COM Module */
#define GPS_BAUDRATE 19200
#define TELEM_BAUDRATE 19200
#define AUXUART_ENABLED 0
#define AUXUART_BAUDRATE 19200
#define TELEM_QUEUE_SIZE 20
#define PIOS_TELEM_STACK_SIZE 2048
/* Stabilization options */
#define PIOS_QUATERNION_STABILIZATION
/* GPS options */
#define PIOS_GPS_SETS_HOMELOCATION
#define HEAP_LIMIT_WARNING 4000
#define HEAP_LIMIT_CRITICAL 1000
#define IRQSTACK_LIMIT_WARNING 150
#define IRQSTACK_LIMIT_CRITICAL 80
#define CPULOAD_LIMIT_WARNING 80
#define CPULOAD_LIMIT_CRITICAL 95
#define REVOLUTION
#endif /* PIOS_CONFIG_POSIX_H */

View File

@ -0,0 +1,46 @@
/**
******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_USB_BOARD Board specific USB definitions
* @brief Board specific USB definitions
* @{
*
* @file pios_usb_board_data.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Board specific USB definitions
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PIOS_USB_BOARD_DATA_H
#define PIOS_USB_BOARD_DATA_H
#define PIOS_USB_BOARD_CDC_DATA_LENGTH 64
#define PIOS_USB_BOARD_CDC_MGMT_LENGTH 32
#define PIOS_USB_BOARD_HID_DATA_LENGTH 64
#define PIOS_USB_BOARD_EP_NUM 4
#include <pios_usb_defs.h> /* USB_* macros */
#define PIOS_USB_BOARD_PRODUCT_ID USB_PRODUCT_ID_REVOLUTION
#define PIOS_USB_BOARD_DEVICE_VER USB_OP_DEVICE_VER(USB_OP_BOARD_ID_REVOLUTION, USB_OP_BOARD_MODE_FW)
#define PIOS_USB_BOARD_SN_SUFFIX "+FW"
#endif /* PIOS_USB_BOARD_DATA_H */

View File

@ -0,0 +1,940 @@
/**
******************************************************************************
* @file pios_board.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
* @author PhoenixPilot, http://github.com/PhoenixPilot, Copyright (C) 2012
* @addtogroup OpenPilotSystem OpenPilot System
* @{
* @addtogroup OpenPilotCore OpenPilot Core
* @{
* @brief Defines board specific static initializers for hardware for the revomini board.
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "inc/openpilot.h"
#include <pios_board_info.h>
#include <uavobjectsinit.h>
#include <hwsettings.h>
#include <manualcontrolsettings.h>
#include <oplinksettings.h>
#include <oplinkstatus.h>
#include <oplinkreceiver.h>
#include <pios_oplinkrcvr_priv.h>
#include <taskinfo.h>
#include <pios_callbackscheduler.h>
/*
* Pull in the board-specific static HW definitions.
* Including .c files is a bit ugly but this allows all of
* the HW definitions to be const and static to limit their
* scope.
*
* NOTE: THIS IS THE ONLY PLACE THAT SHOULD EVER INCLUDE THIS FILE
*/
#include "../board_hw_defs.c"
/**
* Sensor configurations
*/
#if defined(PIOS_INCLUDE_ADC)
#include "pios_adc_priv.h"
void PIOS_ADC_DMC_irq_handler(void);
void DMA2_Stream4_IRQHandler(void) __attribute__((alias("PIOS_ADC_DMC_irq_handler")));
struct pios_adc_cfg pios_adc_cfg = {
.adc_dev = ADC1,
.dma = {
.irq = {
.flags = (DMA_FLAG_TCIF4 | DMA_FLAG_TEIF4 | DMA_FLAG_HTIF4),
.init = {
.NVIC_IRQChannel = DMA2_Stream4_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.rx = {
.channel = DMA2_Stream4,
.init = {
.DMA_Channel = DMA_Channel_0,
.DMA_PeripheralBaseAddr = (uint32_t)&ADC1->DR
},
}
},
.half_flag = DMA_IT_HTIF4,
.full_flag = DMA_IT_TCIF4,
};
void PIOS_ADC_DMC_irq_handler(void)
{
/* Call into the generic code to handle the IRQ for this specific device */
PIOS_ADC_DMA_Handler();
}
#endif /* if defined(PIOS_INCLUDE_ADC) */
#if defined(PIOS_INCLUDE_HMC5883)
#include "pios_hmc5883.h"
static const struct pios_exti_cfg pios_exti_hmc5883_cfg __exti_config = {
.vector = PIOS_HMC5883_IRQHandler,
.line = EXTI_Line7,
.pin = {
.gpio = GPIOB,
.init = {
.GPIO_Pin = GPIO_Pin_7,
.GPIO_Speed = GPIO_Speed_100MHz,
.GPIO_Mode = GPIO_Mode_IN,
.GPIO_OType = GPIO_OType_OD,
.GPIO_PuPd = GPIO_PuPd_NOPULL,
},
},
.irq = {
.init = {
.NVIC_IRQChannel = EXTI9_5_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.exti = {
.init = {
.EXTI_Line = EXTI_Line7, // matches above GPIO pin
.EXTI_Mode = EXTI_Mode_Interrupt,
.EXTI_Trigger = EXTI_Trigger_Rising,
.EXTI_LineCmd = ENABLE,
},
},
};
static const struct pios_hmc5883_cfg pios_hmc5883_cfg = {
.exti_cfg = &pios_exti_hmc5883_cfg,
.M_ODR = PIOS_HMC5883_ODR_75,
.Meas_Conf = PIOS_HMC5883_MEASCONF_NORMAL,
.Gain = PIOS_HMC5883_GAIN_1_9,
.Mode = PIOS_HMC5883_MODE_CONTINUOUS,
};
#endif /* PIOS_INCLUDE_HMC5883 */
/**
* Configuration for the MS5611 chip
*/
#if defined(PIOS_INCLUDE_MS5611)
#include "pios_ms5611.h"
static const struct pios_ms5611_cfg pios_ms5611_cfg = {
.oversampling = MS5611_OSR_512,
};
#endif /* PIOS_INCLUDE_MS5611 */
/**
* Configuration for the MPU6000 chip
*/
#if defined(PIOS_INCLUDE_MPU6000)
#include "pios_mpu6000.h"
#include "pios_mpu6000_config.h"
static const struct pios_exti_cfg pios_exti_mpu6000_cfg __exti_config = {
.vector = PIOS_MPU6000_IRQHandler,
.line = EXTI_Line4,
.pin = {
.gpio = GPIOC,
.init = {
.GPIO_Pin = GPIO_Pin_4,
.GPIO_Speed = GPIO_Speed_100MHz,
.GPIO_Mode = GPIO_Mode_IN,
.GPIO_OType = GPIO_OType_OD,
.GPIO_PuPd = GPIO_PuPd_NOPULL,
},
},
.irq = {
.init = {
.NVIC_IRQChannel = EXTI4_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
.exti = {
.init = {
.EXTI_Line = EXTI_Line4, // matches above GPIO pin
.EXTI_Mode = EXTI_Mode_Interrupt,
.EXTI_Trigger = EXTI_Trigger_Rising,
.EXTI_LineCmd = ENABLE,
},
},
};
static const struct pios_mpu6000_cfg pios_mpu6000_cfg = {
.exti_cfg = &pios_exti_mpu6000_cfg,
.Fifo_store = PIOS_MPU6000_FIFO_TEMP_OUT | PIOS_MPU6000_FIFO_GYRO_X_OUT | PIOS_MPU6000_FIFO_GYRO_Y_OUT | PIOS_MPU6000_FIFO_GYRO_Z_OUT,
// Clock at 8 khz, downsampled by 12 for 666Hz
.Smpl_rate_div_no_dlp = 11,
// with dlp on output rate is 500Hz
.Smpl_rate_div_dlp = 1,
.interrupt_cfg = PIOS_MPU6000_INT_CLR_ANYRD,
.interrupt_en = PIOS_MPU6000_INTEN_DATA_RDY,
.User_ctl = PIOS_MPU6000_USERCTL_FIFO_EN | PIOS_MPU6000_USERCTL_DIS_I2C,
.Pwr_mgmt_clk = PIOS_MPU6000_PWRMGMT_PLL_X_CLK,
.accel_range = PIOS_MPU6000_ACCEL_8G,
.gyro_range = PIOS_MPU6000_SCALE_2000_DEG,
.filter = PIOS_MPU6000_LOWPASS_256_HZ,
.orientation = PIOS_MPU6000_TOP_180DEG
};
#endif /* PIOS_INCLUDE_MPU6000 */
/* One slot per selectable receiver group.
* eg. PWM, PPM, GCS, SPEKTRUM1, SPEKTRUM2, SBUS
* NOTE: No slot in this map for NONE.
*/
uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE];
#define PIOS_COM_TELEM_RF_RX_BUF_LEN 512
#define PIOS_COM_TELEM_RF_TX_BUF_LEN 512
#define PIOS_COM_GPS_RX_BUF_LEN 32
#define PIOS_COM_TELEM_USB_RX_BUF_LEN 65
#define PIOS_COM_TELEM_USB_TX_BUF_LEN 65
#define PIOS_COM_BRIDGE_RX_BUF_LEN 65
#define PIOS_COM_BRIDGE_TX_BUF_LEN 12
#define PIOS_COM_RFM22B_RF_RX_BUF_LEN 512
#define PIOS_COM_RFM22B_RF_TX_BUF_LEN 512
#define PIOS_COM_HKOSD_RX_BUF_LEN 22
#define PIOS_COM_HKOSD_TX_BUF_LEN 22
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
#define PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN 40
uint32_t pios_com_debug_id;
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
uint32_t pios_com_gps_id = 0;
uint32_t pios_com_telem_usb_id = 0;
uint32_t pios_com_telem_rf_id = 0;
uint32_t pios_com_bridge_id = 0;
uint32_t pios_com_overo_id = 0;
uint32_t pios_com_hkosd_id = 0;
uint32_t pios_com_vcp_id = 0;
#if defined(PIOS_INCLUDE_RFM22B)
uint32_t pios_rfm22b_id = 0;
#endif
uintptr_t pios_uavo_settings_fs_id;
uintptr_t pios_user_fs_id;
/*
* Setup a com port based on the passed cfg, driver and buffer sizes. tx size of -1 make the port rx only
*/
static void PIOS_Board_configure_com(const struct pios_usart_cfg *usart_port_cfg, size_t rx_buf_len, size_t tx_buf_len,
const struct pios_com_driver *com_driver, uint32_t *pios_com_id)
{
uint32_t pios_usart_id;
if (PIOS_USART_Init(&pios_usart_id, usart_port_cfg)) {
PIOS_Assert(0);
}
uint8_t *rx_buffer = (uint8_t *)pvPortMalloc(rx_buf_len);
PIOS_Assert(rx_buffer);
if (tx_buf_len != (size_t)-1) { // this is the case for rx/tx ports
uint8_t *tx_buffer = (uint8_t *)pvPortMalloc(tx_buf_len);
PIOS_Assert(tx_buffer);
if (PIOS_COM_Init(pios_com_id, com_driver, pios_usart_id,
rx_buffer, rx_buf_len,
tx_buffer, tx_buf_len)) {
PIOS_Assert(0);
}
} else { // rx only port
if (PIOS_COM_Init(pios_com_id, com_driver, pios_usart_id,
rx_buffer, rx_buf_len,
NULL, 0)) {
PIOS_Assert(0);
}
}
}
static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm_cfg, const struct pios_dsm_cfg *pios_dsm_cfg,
const struct pios_com_driver *usart_com_driver, enum pios_dsm_proto *proto,
ManualControlSettingsChannelGroupsOptions channelgroup, uint8_t *bind)
{
uint32_t pios_usart_dsm_id;
if (PIOS_USART_Init(&pios_usart_dsm_id, pios_usart_dsm_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_dsm_id;
if (PIOS_DSM_Init(&pios_dsm_id, pios_dsm_cfg, usart_com_driver,
pios_usart_dsm_id, *proto, *bind)) {
PIOS_Assert(0);
}
uint32_t pios_dsm_rcvr_id;
if (PIOS_RCVR_Init(&pios_dsm_rcvr_id, &pios_dsm_rcvr_driver, pios_dsm_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[channelgroup] = pios_dsm_rcvr_id;
}
static void PIOS_Board_configure_pwm(const struct pios_pwm_cfg *pwm_cfg)
{
/* Set up the receiver port. Later this should be optional */
uint32_t pios_pwm_id;
PIOS_PWM_Init(&pios_pwm_id, pwm_cfg);
uint32_t pios_pwm_rcvr_id;
if (PIOS_RCVR_Init(&pios_pwm_rcvr_id, &pios_pwm_rcvr_driver, pios_pwm_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PWM] = pios_pwm_rcvr_id;
}
static void PIOS_Board_configure_ppm(const struct pios_ppm_cfg *ppm_cfg)
{
uint32_t pios_ppm_id;
PIOS_PPM_Init(&pios_ppm_id, ppm_cfg);
uint32_t pios_ppm_rcvr_id;
if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM] = pios_ppm_rcvr_id;
}
/**
* PIOS_Board_Init()
* initializes all the core subsystems on this specific hardware
* called from System/openpilot.c
*/
#include <pios_board_info.h>
void PIOS_Board_Init(void)
{
/* Delay system */
PIOS_DELAY_Init();
const struct pios_board_info *bdinfo = &pios_board_info_blob;
#if defined(PIOS_INCLUDE_LED)
const struct pios_gpio_cfg *led_cfg = PIOS_BOARD_HW_DEFS_GetLedCfg(bdinfo->board_rev);
PIOS_Assert(led_cfg);
PIOS_LED_Init(led_cfg);
#endif /* PIOS_INCLUDE_LED */
#if false
/* Set up the SPI interface to the gyro/acelerometer */
if (PIOS_SPI_Init(&pios_spi_gyro_id, &pios_spi_gyro_cfg)) {
PIOS_DEBUG_Assert(0);
}
/* Set up the SPI interface to the flash and rfm22b */
if (PIOS_SPI_Init(&pios_spi_telem_flash_id, &pios_spi_telem_flash_cfg)) {
PIOS_DEBUG_Assert(0);
}
#endif
#if defined(PIOS_INCLUDE_FLASH)
/* Connect flash to the appropriate interface and configure it */
uintptr_t flash_id;
// initialize the internal settings storage flash
if (PIOS_Flash_Internal_Init(&flash_id, &flash_internal_system_cfg)) {
PIOS_DEBUG_Assert(0);
}
if (PIOS_FLASHFS_Logfs_Init(&pios_uavo_settings_fs_id, &flashfs_internal_cfg, &pios_internal_flash_driver, flash_id)) {
PIOS_DEBUG_Assert(0);
}
if (PIOS_FLASHFS_Logfs_Init(&pios_user_fs_id, &flashfs_internal_user_cfg, &pios_internal_flash_driver, flash_id)) {
PIOS_DEBUG_Assert(0);
}
#endif /* if defined(PIOS_INCLUDE_FLASH) */
#if defined(PIOS_INCLUDE_RTC)
PIOS_RTC_Init(&pios_rtc_main_cfg);
#endif
/* IAP System Setup */
PIOS_IAP_Init();
// check for safe mode commands from gcs
if (PIOS_IAP_ReadBootCmd(0) == PIOS_IAP_CLEAR_FLASH_CMD_0 &&
PIOS_IAP_ReadBootCmd(1) == PIOS_IAP_CLEAR_FLASH_CMD_1 &&
PIOS_IAP_ReadBootCmd(2) == PIOS_IAP_CLEAR_FLASH_CMD_2) {
PIOS_FLASHFS_Format(pios_uavo_settings_fs_id);
PIOS_IAP_WriteBootCmd(0, 0);
PIOS_IAP_WriteBootCmd(1, 0);
PIOS_IAP_WriteBootCmd(2, 0);
}
#ifdef PIOS_INCLUDE_WDG
PIOS_WDG_Init();
#endif
/* Initialize the task monitor */
if (PIOS_TASK_MONITOR_Initialize(TASKINFO_RUNNING_NUMELEM)) {
PIOS_Assert(0);
}
/* Initialize the delayed callback library */
PIOS_CALLBACKSCHEDULER_Initialize();
/* Initialize UAVObject libraries */
EventDispatcherInitialize();
UAVObjInitialize();
HwSettingsInitialize();
#if defined(PIOS_INCLUDE_RFM22B)
OPLinkSettingsInitialize();
OPLinkStatusInitialize();
#endif /* PIOS_INCLUDE_RFM22B */
/* Initialize the alarms library */
AlarmsInitialize();
/* Set up pulse timers */
PIOS_TIM_InitClock(&tim_1_cfg);
PIOS_TIM_InitClock(&tim_3_cfg);
PIOS_TIM_InitClock(&tim_4_cfg);
PIOS_TIM_InitClock(&tim_5_cfg);
PIOS_TIM_InitClock(&tim_8_cfg);
PIOS_TIM_InitClock(&tim_9_cfg);
PIOS_TIM_InitClock(&tim_10_cfg);
PIOS_TIM_InitClock(&tim_11_cfg);
PIOS_TIM_InitClock(&tim_12_cfg);
uint16_t boot_count = PIOS_IAP_ReadBootCount();
if (boot_count < 3) {
PIOS_IAP_WriteBootCount(++boot_count);
AlarmsClear(SYSTEMALARMS_ALARM_BOOTFAULT);
} else {
/* Too many failed boot attempts, force hwsettings to defaults */
HwSettingsSetDefaults(HwSettingsHandle(), 0);
AlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT, SYSTEMALARMS_ALARM_CRITICAL);
}
// PIOS_IAP_Init();
#if defined(PIOS_INCLUDE_USB)
/* Initialize board specific USB data */
PIOS_USB_BOARD_DATA_Init();
/* Flags to determine if various USB interfaces are advertised */
bool usb_hid_present = false;
bool usb_cdc_present = false;
#if defined(PIOS_INCLUDE_USB_CDC)
if (PIOS_USB_DESC_HID_CDC_Init()) {
PIOS_Assert(0);
}
usb_hid_present = true;
usb_cdc_present = true;
#else
if (PIOS_USB_DESC_HID_ONLY_Init()) {
PIOS_Assert(0);
}
usb_hid_present = true;
#endif
uint32_t pios_usb_id;
PIOS_USB_Init(&pios_usb_id, PIOS_BOARD_HW_DEFS_GetUsbCfg(bdinfo->board_rev));
#if defined(PIOS_INCLUDE_USB_CDC)
uint8_t hwsettings_usb_vcpport;
/* Configure the USB VCP port */
HwSettingsUSB_VCPPortGet(&hwsettings_usb_vcpport);
if (!usb_cdc_present) {
/* Force VCP port function to disabled if we haven't advertised VCP in our USB descriptor */
hwsettings_usb_vcpport = HWSETTINGS_USB_VCPPORT_DISABLED;
}
uint32_t pios_usb_cdc_id;
if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) {
PIOS_Assert(0);
}
uint32_t pios_usb_hid_id;
if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) {
PIOS_Assert(0);
}
switch (hwsettings_usb_vcpport) {
case HWSETTINGS_USB_VCPPORT_DISABLED:
break;
case HWSETTINGS_USB_VCPPORT_USBTELEMETRY:
#if defined(PIOS_INCLUDE_COM)
{
uint8_t *rx_buffer = (uint8_t *)pvPortMalloc(PIOS_COM_TELEM_USB_RX_BUF_LEN);
uint8_t *tx_buffer = (uint8_t *)pvPortMalloc(PIOS_COM_TELEM_USB_TX_BUF_LEN);
PIOS_Assert(rx_buffer);
PIOS_Assert(tx_buffer);
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id,
rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN,
tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) {
PIOS_Assert(0);
}
}
#endif /* PIOS_INCLUDE_COM */
break;
case HWSETTINGS_USB_VCPPORT_COMBRIDGE:
#if defined(PIOS_INCLUDE_COM)
{
uint8_t *rx_buffer = (uint8_t *)pvPortMalloc(PIOS_COM_BRIDGE_RX_BUF_LEN);
uint8_t *tx_buffer = (uint8_t *)pvPortMalloc(PIOS_COM_BRIDGE_TX_BUF_LEN);
PIOS_Assert(rx_buffer);
PIOS_Assert(tx_buffer);
if (PIOS_COM_Init(&pios_com_vcp_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id,
rx_buffer, PIOS_COM_BRIDGE_RX_BUF_LEN,
tx_buffer, PIOS_COM_BRIDGE_TX_BUF_LEN)) {
PIOS_Assert(0);
}
}
#endif /* PIOS_INCLUDE_COM */
break;
case HWSETTINGS_USB_VCPPORT_DEBUGCONSOLE:
#if defined(PIOS_INCLUDE_COM)
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
{
uint8_t *tx_buffer = (uint8_t *)pvPortMalloc(PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN);
PIOS_Assert(tx_buffer);
if (PIOS_COM_Init(&pios_com_debug_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id,
NULL, 0,
tx_buffer, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN)) {
PIOS_Assert(0);
}
}
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
#endif /* PIOS_INCLUDE_COM */
break;
}
#endif /* PIOS_INCLUDE_USB_CDC */
#if defined(PIOS_INCLUDE_USB_HID)
/* Configure the usb HID port */
uint8_t hwsettings_usb_hidport;
HwSettingsUSB_HIDPortGet(&hwsettings_usb_hidport);
if (!usb_hid_present) {
/* Force HID port function to disabled if we haven't advertised HID in our USB descriptor */
hwsettings_usb_hidport = HWSETTINGS_USB_HIDPORT_DISABLED;
}
switch (hwsettings_usb_hidport) {
case HWSETTINGS_USB_HIDPORT_DISABLED:
break;
case HWSETTINGS_USB_HIDPORT_USBTELEMETRY:
#if defined(PIOS_INCLUDE_COM)
{
uint8_t *rx_buffer = (uint8_t *)pvPortMalloc(PIOS_COM_TELEM_USB_RX_BUF_LEN);
uint8_t *tx_buffer = (uint8_t *)pvPortMalloc(PIOS_COM_TELEM_USB_TX_BUF_LEN);
PIOS_Assert(rx_buffer);
PIOS_Assert(tx_buffer);
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id,
rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN,
tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) {
PIOS_Assert(0);
}
}
#endif /* PIOS_INCLUDE_COM */
break;
}
#endif /* PIOS_INCLUDE_USB_HID */
if (usb_hid_present || usb_cdc_present) {
PIOS_USBHOOK_Activate();
}
#endif /* PIOS_INCLUDE_USB */
/* Configure IO ports */
uint8_t hwsettings_DSMxBind;
HwSettingsDSMxBindGet(&hwsettings_DSMxBind);
/* Configure main USART port */
uint8_t hwsettings_mainport;
HwSettingsRM_MainPortGet(&hwsettings_mainport);
switch (hwsettings_mainport) {
case HWSETTINGS_RM_MAINPORT_DISABLED:
break;
case HWSETTINGS_RM_MAINPORT_TELEMETRY:
PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id);
break;
case HWSETTINGS_RM_MAINPORT_GPS:
PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_GPS_RX_BUF_LEN, -1, &pios_usart_com_driver, &pios_com_gps_id);
break;
case HWSETTINGS_RM_MAINPORT_SBUS:
#if defined(PIOS_INCLUDE_SBUS)
{
uint32_t pios_usart_sbus_id;
if (PIOS_USART_Init(&pios_usart_sbus_id, &pios_usart_sbus_main_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_sbus_id;
if (PIOS_SBus_Init(&pios_sbus_id, &pios_sbus_cfg, &pios_usart_com_driver, pios_usart_sbus_id)) {
PIOS_Assert(0);
}
uint32_t pios_sbus_rcvr_id;
if (PIOS_RCVR_Init(&pios_sbus_rcvr_id, &pios_sbus_rcvr_driver, pios_sbus_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS] = pios_sbus_rcvr_id;
}
#endif
break;
case HWSETTINGS_RM_MAINPORT_DSM2:
case HWSETTINGS_RM_MAINPORT_DSMX10BIT:
case HWSETTINGS_RM_MAINPORT_DSMX11BIT:
{
enum pios_dsm_proto proto;
switch (hwsettings_mainport) {
case HWSETTINGS_RM_MAINPORT_DSM2:
proto = PIOS_DSM_PROTO_DSM2;
break;
case HWSETTINGS_RM_MAINPORT_DSMX10BIT:
proto = PIOS_DSM_PROTO_DSMX10BIT;
break;
case HWSETTINGS_RM_MAINPORT_DSMX11BIT:
proto = PIOS_DSM_PROTO_DSMX11BIT;
break;
default:
PIOS_Assert(0);
break;
}
// Force binding to zero on the main port
hwsettings_DSMxBind = 0;
// TODO: Define the various Channelgroup for Revo dsm inputs and handle here
PIOS_Board_configure_dsm(&pios_usart_dsm_main_cfg, &pios_dsm_main_cfg,
&pios_usart_com_driver, &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT, &hwsettings_DSMxBind);
}
break;
case HWSETTINGS_RM_MAINPORT_DEBUGCONSOLE:
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
{
PIOS_Board_configure_com(&pios_usart_main_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id);
}
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
break;
case HWSETTINGS_RM_MAINPORT_COMBRIDGE:
PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id);
break;
case HWSETTINGS_RM_MAINPORT_OSDHK:
PIOS_Board_configure_com(&pios_usart_hkosd_main_cfg, PIOS_COM_HKOSD_RX_BUF_LEN, PIOS_COM_HKOSD_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hkosd_id);
break;
} /* hwsettings_rm_mainport */
if (hwsettings_mainport != HWSETTINGS_RM_MAINPORT_SBUS) {
GPIO_Init(pios_sbus_cfg.inv.gpio, &pios_sbus_cfg.inv.init);
GPIO_WriteBit(pios_sbus_cfg.inv.gpio, pios_sbus_cfg.inv.init.GPIO_Pin, pios_sbus_cfg.gpio_inv_disable);
}
/* Configure FlexiPort */
uint8_t hwsettings_flexiport;
HwSettingsRM_FlexiPortGet(&hwsettings_flexiport);
switch (hwsettings_flexiport) {
case HWSETTINGS_RM_FLEXIPORT_DISABLED:
break;
case HWSETTINGS_RM_FLEXIPORT_TELEMETRY:
PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id);
break;
case HWSETTINGS_RM_FLEXIPORT_I2C:
#if defined(PIOS_INCLUDE_I2C)
{
if (PIOS_I2C_Init(&pios_i2c_flexiport_adapter_id, &pios_i2c_flexiport_adapter_cfg)) {
PIOS_Assert(0);
}
}
#endif /* PIOS_INCLUDE_I2C */
break;
case HWSETTINGS_RM_FLEXIPORT_GPS:
PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_GPS_RX_BUF_LEN, -1, &pios_usart_com_driver, &pios_com_gps_id);
break;
case HWSETTINGS_RM_FLEXIPORT_DSM2:
case HWSETTINGS_RM_FLEXIPORT_DSMX10BIT:
case HWSETTINGS_RM_FLEXIPORT_DSMX11BIT:
{
enum pios_dsm_proto proto;
switch (hwsettings_flexiport) {
case HWSETTINGS_RM_FLEXIPORT_DSM2:
proto = PIOS_DSM_PROTO_DSM2;
break;
case HWSETTINGS_RM_FLEXIPORT_DSMX10BIT:
proto = PIOS_DSM_PROTO_DSMX10BIT;
break;
case HWSETTINGS_RM_FLEXIPORT_DSMX11BIT:
proto = PIOS_DSM_PROTO_DSMX11BIT;
break;
default:
PIOS_Assert(0);
break;
}
// TODO: Define the various Channelgroup for Revo dsm inputs and handle here
PIOS_Board_configure_dsm(&pios_usart_dsm_flexi_cfg, &pios_dsm_flexi_cfg,
&pios_usart_com_driver, &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMFLEXIPORT, &hwsettings_DSMxBind);
}
break;
case HWSETTINGS_RM_FLEXIPORT_DEBUGCONSOLE:
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
{
PIOS_Board_configure_com(&pios_usart_main_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id);
}
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
break;
case HWSETTINGS_RM_FLEXIPORT_COMBRIDGE:
PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id);
break;
case HWSETTINGS_RM_FLEXIPORT_OSDHK:
PIOS_Board_configure_com(&pios_usart_hkosd_flexi_cfg, PIOS_COM_HKOSD_RX_BUF_LEN, PIOS_COM_HKOSD_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hkosd_id);
break;
} /* hwsettings_rm_flexiport */
/* Initalize the RFM22B radio COM device. */
#if defined(PIOS_INCLUDE_RFM22B)
/* Fetch the OPinkSettings object. */
OPLinkSettingsData oplinkSettings;
OPLinkSettingsGet(&oplinkSettings);
// Initialize out status object.
OPLinkStatusData oplinkStatus;
OPLinkStatusGet(&oplinkStatus);
oplinkStatus.BoardType = bdinfo->board_type;
PIOS_BL_HELPER_FLASH_Read_Description(oplinkStatus.Description, OPLINKSTATUS_DESCRIPTION_NUMELEM);
PIOS_SYS_SerialNumberGetBinary(oplinkStatus.CPUSerial);
oplinkStatus.BoardRevision = bdinfo->board_rev;
/* Is the radio turned on? */
bool is_coordinator = (oplinkSettings.Coordinator == OPLINKSETTINGS_COORDINATOR_TRUE);
bool is_oneway = (oplinkSettings.OneWay == OPLINKSETTINGS_ONEWAY_TRUE);
bool ppm_mode = (oplinkSettings.PPM == OPLINKSETTINGS_PPM_TRUE);
bool ppm_only = (oplinkSettings.PPMOnly == OPLINKSETTINGS_PPMONLY_TRUE);
if (oplinkSettings.MaxRFPower != OPLINKSETTINGS_MAXRFPOWER_0) {
/* Configure the RFM22B device. */
const struct pios_rfm22b_cfg *rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(bdinfo->board_rev);
if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, rfm22b_cfg->slave_num, rfm22b_cfg)) {
PIOS_Assert(0);
}
/* Configure the radio com interface */
uint8_t *rx_buffer = (uint8_t *)pvPortMalloc(PIOS_COM_RFM22B_RF_RX_BUF_LEN);
uint8_t *tx_buffer = (uint8_t *)pvPortMalloc(PIOS_COM_RFM22B_RF_TX_BUF_LEN);
PIOS_Assert(rx_buffer);
PIOS_Assert(tx_buffer);
if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_rfm22b_com_driver, pios_rfm22b_id,
rx_buffer, PIOS_COM_RFM22B_RF_RX_BUF_LEN,
tx_buffer, PIOS_COM_RFM22B_RF_TX_BUF_LEN)) {
PIOS_Assert(0);
}
oplinkStatus.LinkState = OPLINKSTATUS_LINKSTATE_ENABLED;
// Set the RF data rate on the modem to ~2X the selected buad rate because the modem is half duplex.
enum rfm22b_datarate datarate = RFM22_datarate_64000;
switch (oplinkSettings.ComSpeed) {
case OPLINKSETTINGS_COMSPEED_4800:
datarate = RFM22_datarate_9600;
break;
case OPLINKSETTINGS_COMSPEED_9600:
datarate = RFM22_datarate_19200;
break;
case OPLINKSETTINGS_COMSPEED_19200:
datarate = RFM22_datarate_32000;
break;
case OPLINKSETTINGS_COMSPEED_38400:
datarate = RFM22_datarate_64000;
break;
case OPLINKSETTINGS_COMSPEED_57600:
datarate = RFM22_datarate_100000;
break;
case OPLINKSETTINGS_COMSPEED_115200:
datarate = RFM22_datarate_192000;
break;
}
/* Set the radio configuration parameters. */
PIOS_RFM22B_SetChannelConfig(pios_rfm22b_id, datarate, oplinkSettings.MinChannel, oplinkSettings.MaxChannel, oplinkSettings.ChannelSet, is_coordinator, is_oneway, ppm_mode, ppm_only);
PIOS_RFM22B_SetCoordinatorID(pios_rfm22b_id, oplinkSettings.CoordID);
/* Set the PPM callback if we should be receiving PPM. */
if (ppm_mode) {
PIOS_RFM22B_SetPPMCallback(pios_rfm22b_id, PIOS_Board_PPM_callback);
}
/* Set the modem Tx poer level */
switch (oplinkSettings.MaxRFPower) {
case OPLINKSETTINGS_MAXRFPOWER_125:
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_0);
break;
case OPLINKSETTINGS_MAXRFPOWER_16:
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_1);
break;
case OPLINKSETTINGS_MAXRFPOWER_316:
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_2);
break;
case OPLINKSETTINGS_MAXRFPOWER_63:
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_3);
break;
case OPLINKSETTINGS_MAXRFPOWER_126:
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_4);
break;
case OPLINKSETTINGS_MAXRFPOWER_25:
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_5);
break;
case OPLINKSETTINGS_MAXRFPOWER_50:
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_6);
break;
case OPLINKSETTINGS_MAXRFPOWER_100:
PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_7);
break;
default:
// do nothing
break;
}
/* Reinitialize the modem. */
PIOS_RFM22B_Reinit(pios_rfm22b_id);
} else {
oplinkStatus.LinkState = OPLINKSTATUS_LINKSTATE_DISABLED;
}
OPLinkStatusSet(&oplinkStatus);
#endif /* PIOS_INCLUDE_RFM22B */
#if defined(PIOS_INCLUDE_PWM) || defined(PIOS_INCLUDE_PWM)
const struct pios_servo_cfg *pios_servo_cfg;
// default to servo outputs only
pios_servo_cfg = &pios_servo_cfg_out;
#endif
/* Configure the receiver port*/
uint8_t hwsettings_rcvrport;
HwSettingsRM_RcvrPortGet(&hwsettings_rcvrport);
//
switch (hwsettings_rcvrport) {
case HWSETTINGS_RM_RCVRPORT_DISABLED:
break;
case HWSETTINGS_RM_RCVRPORT_PWM:
#if defined(PIOS_INCLUDE_PWM)
/* Set up the receiver port. Later this should be optional */
PIOS_Board_configure_pwm(&pios_pwm_cfg);
#endif /* PIOS_INCLUDE_PWM */
break;
case HWSETTINGS_RM_RCVRPORT_PPM:
case HWSETTINGS_RM_RCVRPORT_PPMOUTPUTS:
case HWSETTINGS_RM_RCVRPORT_PPMPWM:
#if defined(PIOS_INCLUDE_PPM)
if (hwsettings_rcvrport == HWSETTINGS_RM_RCVRPORT_PPMOUTPUTS) {
// configure servo outputs and the remaining 5 inputs as outputs
pios_servo_cfg = &pios_servo_cfg_out_in_ppm;
}
PIOS_Board_configure_ppm(&pios_ppm_cfg);
// enable pwm on the remaining channels
if (hwsettings_rcvrport == HWSETTINGS_RM_RCVRPORT_PPMPWM) {
PIOS_Board_configure_pwm(&pios_pwm_ppm_cfg);
}
break;
#endif /* PIOS_INCLUDE_PPM */
case HWSETTINGS_RM_RCVRPORT_OUTPUTS:
// configure only the servo outputs
pios_servo_cfg = &pios_servo_cfg_out_in;
break;
}
#if defined(PIOS_INCLUDE_GCSRCVR)
GCSReceiverInitialize();
uint32_t pios_gcsrcvr_id;
PIOS_GCSRCVR_Init(&pios_gcsrcvr_id);
uint32_t pios_gcsrcvr_rcvr_id;
if (PIOS_RCVR_Init(&pios_gcsrcvr_rcvr_id, &pios_gcsrcvr_rcvr_driver, pios_gcsrcvr_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_GCS] = pios_gcsrcvr_rcvr_id;
#endif /* PIOS_INCLUDE_GCSRCVR */
#if defined(PIOS_INCLUDE_OPLINKRCVR)
{
OPLinkReceiverInitialize();
uint32_t pios_oplinkrcvr_id;
PIOS_OPLinkRCVR_Init(&pios_oplinkrcvr_id);
uint32_t pios_oplinkrcvr_rcvr_id;
if (PIOS_RCVR_Init(&pios_oplinkrcvr_rcvr_id, &pios_oplinkrcvr_rcvr_driver, pios_oplinkrcvr_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_OPLINK] = pios_oplinkrcvr_rcvr_id;
}
#endif /* PIOS_INCLUDE_OPLINKRCVR */
#ifndef PIOS_ENABLE_DEBUG_PINS
// pios_servo_cfg points to the correct configuration based on input port settings
PIOS_Servo_Init(pios_servo_cfg);
#else
PIOS_DEBUG_Init(pios_tim_servoport_all_pins, NELEMENTS(pios_tim_servoport_all_pins));
#endif
// Disable GPIO_A8 Pullup to prevent wrong results on battery voltage readout
GPIO_InitTypeDef gpioA8 = {
.GPIO_Speed = GPIO_Speed_2MHz,
.GPIO_Mode = GPIO_Mode_IN,
.GPIO_PuPd = GPIO_PuPd_NOPULL,
.GPIO_Pin = GPIO_Pin_8,
.GPIO_OType = GPIO_OType_OD,
};
GPIO_Init(GPIOA, &gpioA8);
if (PIOS_I2C_Init(&pios_i2c_mag_pressure_adapter_id, &pios_i2c_mag_pressure_adapter_cfg)) {
PIOS_DEBUG_Assert(0);
}
PIOS_DELAY_WaitmS(50);
#if defined(PIOS_INCLUDE_ADC)
PIOS_ADC_Init(&pios_adc_cfg);
#endif
#if defined(PIOS_INCLUDE_HMC5883)
PIOS_HMC5883_Init(&pios_hmc5883_cfg);
#endif
#if defined(PIOS_INCLUDE_MS5611)
PIOS_MS5611_Init(&pios_ms5611_cfg, pios_i2c_mag_pressure_adapter_id);
#endif
#if defined(PIOS_INCLUDE_MPU6000)
PIOS_MPU6000_Init(pios_spi_gyro_id, 0, &pios_mpu6000_cfg);
PIOS_MPU6000_CONFIG_Configure();
#endif
}
/**
* @}
* @}
*/

View File

@ -0,0 +1,227 @@
/**
******************************************************************************
*
* @file pios_board.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Defines board specific static initializers for hardware for the OpenPilot board.
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "inc/openpilot.h"
#include <pios_com_priv.h>
#include <pios_tcp_priv.h>
#include <pios_udp_priv.h>
#include <pios_rcvr_priv.h>
#include <pios_gcsrcvr_priv.h>
#include <uavobjectsinit.h>
#include <accelssensor.h>
#include <barosensor.h>
#include <gpspositionsensor.h>
#include <gyrosensor.h>
#include <magsensor.h>
#include <manualcontrolsettings.h>
void Stack_Change() {}
void Stack_Change_Weak() {}
const struct pios_tcp_cfg pios_tcp_telem_cfg = {
.ip = "0.0.0.0",
.port = 9001,
};
const struct pios_udp_cfg pios_udp_telem_cfg = {
.ip = "0.0.0.0",
.port = 9001,
};
const struct pios_tcp_cfg pios_tcp_gps_cfg = {
.ip = "0.0.0.0",
.port = 9001,
};
const struct pios_tcp_cfg pios_tcp_debug_cfg = {
.ip = "0.0.0.0",
.port = 9002,
};
#ifdef PIOS_COM_AUX
/*
* AUX USART
*/
const struct pios_tcp_cfg pios_tcp_aux_cfg = {
.ip = "0.0.0.0",
.port = 9003,
};
#endif
#define PIOS_COM_TELEM_RF_RX_BUF_LEN 192
#define PIOS_COM_TELEM_RF_TX_BUF_LEN 192
#define PIOS_COM_GPS_RX_BUF_LEN 96
/*
* Board specific number of devices.
*/
/*
struct pios_udp_dev pios_udp_devs[] = {
#define PIOS_UDP_TELEM 0
{
.cfg = &pios_udp0_cfg,
},
#define PIOS_UDP_GPS 1
{
.cfg = &pios_udp1_cfg,
},
#define PIOS_UDP_LOCAL 2
{
.cfg = &pios_udp2_cfg,
},
#ifdef PIOS_COM_AUX
#define PIOS_UDP_AUX 3
{
.cfg = &pios_udp3_cfg,
},
#endif
};
uint8_t pios_udp_num_devices = NELEMENTS(pios_udp_devs);
*/
/*
* COM devices
*/
/*
* Board specific number of devices.
*/
extern const struct pios_com_driver pios_serial_com_driver;
extern const struct pios_com_driver pios_udp_com_driver;
extern const struct pios_com_driver pios_tcp_com_driver;
uint32_t pios_com_telem_rf_id;
uint32_t pios_com_telem_usb_id;
uint32_t pios_com_gps_id;
uint32_t pios_com_aux_id;
uint32_t pios_com_spectrum_id;
uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE];
/**
* PIOS_Board_Init()
* initializes all the core systems on this specific hardware
* called from System/openpilot.c
*/
void PIOS_Board_Init(void)
{
/* Delay system */
PIOS_DELAY_Init();
/* Initialize the delayed callback library */
CallbackSchedulerInitialize();
/* Initialize UAVObject libraries */
EventDispatcherInitialize();
UAVObjInitialize();
UAVObjectsInitializeAll();
AccelSensorInitialize();
BaroSensorInitialize();
MagSensorInitialize();
GPSPositionSensorInitialize();
GyroSensorInitialize();
/* Initialize the alarms library */
AlarmsInitialize();
/* Initialize the task monitor */
if (PIOS_TASK_MONITOR_Initialize(TASKINFO_RUNNING_NUMELEM)) {
PIOS_Assert(0);
}
#if defined(PIOS_INCLUDE_COM)
#if defined(PIOS_INCLUDE_TELEMETRY_RF) && 1
{
uint32_t pios_tcp_telem_rf_id;
if (PIOS_TCP_Init(&pios_tcp_telem_rf_id, &pios_tcp_telem_cfg)) {
PIOS_Assert(0);
}
uint8_t *rx_buffer = (uint8_t *)pvPortMalloc(PIOS_COM_TELEM_RF_RX_BUF_LEN);
uint8_t *tx_buffer = (uint8_t *)pvPortMalloc(PIOS_COM_TELEM_RF_TX_BUF_LEN);
PIOS_Assert(rx_buffer);
PIOS_Assert(tx_buffer);
if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_tcp_com_driver, pios_tcp_telem_rf_id,
rx_buffer, PIOS_COM_TELEM_RF_RX_BUF_LEN,
tx_buffer, PIOS_COM_TELEM_RF_TX_BUF_LEN)) {
PIOS_Assert(0);
}
}
#endif /* PIOS_INCLUDE_TELEMETRY_RF */
#if defined(PIOS_INCLUDE_TELEMETRY_RF) && 0
{
uint32_t pios_udp_telem_rf_id;
if (PIOS_UDP_Init(&pios_udp_telem_rf_id, &pios_udp_telem_cfg)) {
PIOS_Assert(0);
}
uint8_t *rx_buffer = (uint8_t *)pvPortMalloc(PIOS_COM_TELEM_RF_RX_BUF_LEN);
uint8_t *tx_buffer = (uint8_t *)pvPortMalloc(PIOS_COM_TELEM_RF_TX_BUF_LEN);
PIOS_Assert(rx_buffer);
PIOS_Assert(tx_buffer);
if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_udp_com_driver, pios_udp_telem_rf_id,
rx_buffer, PIOS_COM_TELEM_RF_RX_BUF_LEN,
tx_buffer, PIOS_COM_TELEM_RF_TX_BUF_LEN)) {
PIOS_Assert(0);
}
}
#endif /* PIOS_INCLUDE_TELEMETRY_RF */
#if defined(PIOS_INCLUDE_GPS)
{
uint32_t pios_tcp_gps_id;
if (PIOS_TCP_Init(&pios_tcp_gps_id, &pios_tcp_gps_cfg)) {
PIOS_Assert(0);
}
uint8_t *rx_buffer = (uint8_t *)pvPortMalloc(PIOS_COM_GPS_RX_BUF_LEN);
PIOS_Assert(rx_buffer);
if (PIOS_COM_Init(&pios_com_gps_id, &pios_tcp_com_driver, pios_tcp_gps_id,
rx_buffer, PIOS_COM_GPS_RX_BUF_LEN,
NULL, 0)) {
PIOS_Assert(0);
}
}
#endif /* PIOS_INCLUDE_GPS */
#endif /* if defined(PIOS_INCLUDE_COM) */
#if defined(PIOS_INCLUDE_GCSRCVR)
GCSReceiverInitialize();
uint32_t pios_gcsrcvr_id;
PIOS_GCSRCVR_Init(&pios_gcsrcvr_id);
uint32_t pios_gcsrcvr_rcvr_id;
if (PIOS_RCVR_Init(&pios_gcsrcvr_rcvr_id, &pios_gcsrcvr_rcvr_driver, pios_gcsrcvr_id)) {
PIOS_Assert(0);
}
pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_GCS] = pios_gcsrcvr_rcvr_id;
#endif /* PIOS_INCLUDE_GCSRCVR */
}
/**
* @}
*/

View File

@ -0,0 +1,294 @@
/**
******************************************************************************
* @addtogroup OpenPilotSystem OpenPilot System
* @{
* @addtogroup OpenPilotCore OpenPilot Core
* @{
* @file pios_board.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
* @brief Defines board hardware for the OpenPilot Version 1.1 hardware.
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PIOS_BOARD_H
#define PIOS_BOARD_H
#include <stdbool.h>
// ------------------------
// Timers and Channels Used
// ------------------------
/*
Timer | Channel 1 | Channel 2 | Channel 3 | Channel 4
------+-----------+-----------+-----------+----------
TIM1 | | | |
TIM2 | --------------- PIOS_DELAY -----------------
TIM3 | | | |
TIM4 | | | |
TIM5 | | | |
TIM6 | | | |
TIM7 | | | |
TIM8 | | | |
------+-----------+-----------+-----------+----------
*/
// ------------------------
// DMA Channels Used
// ------------------------
/* Channel 1 - */
/* Channel 2 - SPI1 RX */
/* Channel 3 - SPI1 TX */
/* Channel 4 - SPI2 RX */
/* Channel 5 - SPI2 TX */
/* Channel 6 - */
/* Channel 7 - */
/* Channel 8 - */
/* Channel 9 - */
/* Channel 10 - */
/* Channel 11 - */
/* Channel 12 - */
// ------------------------
// BOOTLOADER_SETTINGS
// ------------------------
#define BOARD_READABLE true
#define BOARD_WRITABLE true
#define MAX_DEL_RETRYS 3
// ------------------------
// PIOS_LED
// ------------------------
#define PIOS_LED_HEARTBEAT 0
#define PIOS_LED_ALARM 1
#define PIOS_LED_D1 2
#define PIOS_LED_D2 3
#define PIOS_LED_D3 4
#define PIOS_LED_D4 5
// ------------------------
// PIOS_SPI
// See also pios_board.c
// ------------------------
#define PIOS_SPI_MAX_DEVS 3
// ------------------------
// PIOS_WDG
// ------------------------
#define PIOS_WATCHDOG_TIMEOUT 250
#define PIOS_WDG_REGISTER RTC_BKP_DR4
#define PIOS_WDG_ACTUATOR 0x0001
#define PIOS_WDG_STABILIZATION 0x0002
#define PIOS_WDG_ATTITUDE 0x0004
#define PIOS_WDG_MANUAL 0x0008
#define PIOS_WDG_SENSORS 0x0010
// ------------------------
// PIOS_I2C
// See also pios_board.c
// ------------------------
#define PIOS_I2C_MAX_DEVS 3
extern uint32_t pios_i2c_mag_pressure_adapter_id;
#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_mag_pressure_adapter_id)
extern uint32_t pios_i2c_flexiport_adapter_id;
#define PIOS_I2C_FLEXI_ADAPTER (pios_i2c_flexiport_adapter_id)
#define PIOS_I2C_ETASV3_ADAPTER (PIOS_I2C_FLEXI_ADAPTER)
// -------------------------
// PIOS_USART
//
// See also pios_board.c
// -------------------------
#define PIOS_USART_MAX_DEVS 5
// -------------------------
// PIOS_COM
//
// See also pios_board.c
// -------------------------
#define PIOS_COM_MAX_DEVS 4
extern uint32_t pios_com_telem_rf_id;
extern uint32_t pios_com_gps_id;
extern uint32_t pios_com_telem_usb_id;
extern uint32_t pios_com_bridge_id;
extern uint32_t pios_com_vcp_id;
extern uint32_t pios_com_hkosd_id;
#define PIOS_COM_GPS (pios_com_gps_id)
#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id)
#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id)
#define PIOS_COM_BRIDGE (pios_com_bridge_id)
#define PIOS_COM_VCP (pios_com_vcp_id)
#define PIOS_COM_OSDHK (pios_com_hkosd_id)
#if defined(PIOS_INCLUDE_DEBUG_CONSOLE)
extern uint32_t pios_com_debug_id;
#define PIOS_COM_DEBUG (pios_com_debug_id)
#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */
#if defined(PIOS_INCLUDE_RFM22B)
extern uint32_t pios_rfm22b_id;
extern uint32_t pios_spi_telem_flash_id;
#define PIOS_RFM22_SPI_PORT (pios_spi_telem_flash_id)
#endif /* PIOS_INCLUDE_RFM22B */
// -------------------------
// Packet Handler
// -------------------------
#define RS_ECC_NPARITY 4
#define PIOS_PH_MAX_PACKET 255
#define PIOS_PH_WIN_SIZE 3
#define PIOS_PH_MAX_CONNECTIONS 1
extern uint32_t pios_packet_handler;
#define PIOS_PACKET_HANDLER (pios_packet_handler)
// ------------------------
// TELEMETRY
// ------------------------
#define TELEM_QUEUE_SIZE 80
#define PIOS_TELEM_STACK_SIZE 800
// -------------------------
// System Settings
//
// See also System_stm32f4xx.c
// -------------------------
// These macros are deprecated
// please use PIOS_PERIPHERAL_APBx_CLOCK According to the table below
// #define PIOS_MASTER_CLOCK
// #define PIOS_PERIPHERAL_CLOCK
// #define PIOS_PERIPHERAL_CLOCK
#define PIOS_SYSCLK 168000000
// Peripherals that belongs to APB1 are:
// DAC |PWR |CAN1,2
// I2C1,2,3 |UART4,5 |USART3,2
// I2S3Ext |SPI3/I2S3 |SPI2/I2S2
// I2S2Ext |IWDG |WWDG
// RTC/BKP reg
// TIM2,3,4,5,6,7,12,13,14
// Calculated as SYSCLK / APBPresc * (APBPre == 1 ? 1 : 2)
// Default APB1 Prescaler = 4
#define PIOS_PERIPHERAL_APB1_CLOCK (PIOS_SYSCLK / 2)
// Peripherals belonging to APB2
// SDIO |EXTI |SYSCFG |SPI1
// ADC1,2,3
// USART1,6
// TIM1,8,9,10,11
//
// Default APB2 Prescaler = 2
//
#define PIOS_PERIPHERAL_APB2_CLOCK PIOS_SYSCLK
// -------------------------
// Interrupt Priorities
// -------------------------
#define PIOS_IRQ_PRIO_LOW 12 // lower than RTOS
#define PIOS_IRQ_PRIO_MID 8 // higher than RTOS
#define PIOS_IRQ_PRIO_HIGH 5 // for SPI, ADC, I2C etc...
#define PIOS_IRQ_PRIO_HIGHEST 4 // for USART etc...
// ------------------------
// PIOS_RCVR
// See also pios_board.c
// ------------------------
#define PIOS_RCVR_MAX_DEVS 3
#define PIOS_RCVR_MAX_CHANNELS 12
#define PIOS_GCSRCVR_TIMEOUT_MS 100
#define PIOS_RFM22B_RCVR_TIMEOUT_MS 200
#define PIOS_OPLINK_RCVR_TIMEOUT_MS 100
// -------------------------
// Receiver PPM input
// -------------------------
#define PIOS_PPM_MAX_DEVS 1
#define PIOS_PPM_NUM_INPUTS 12
// -------------------------
// Receiver PWM input
// -------------------------
#define PIOS_PWM_MAX_DEVS 1
#define PIOS_PWM_NUM_INPUTS 8
// -------------------------
// Receiver SPEKTRUM input
// -------------------------
#define PIOS_SPEKTRUM_MAX_DEVS 2
#define PIOS_SPEKTRUM_NUM_INPUTS 12
// -------------------------
// Receiver S.Bus input
// -------------------------
#define PIOS_SBUS_MAX_DEVS 1
#define PIOS_SBUS_NUM_INPUTS (16 + 2)
// -------------------------
// Receiver DSM input
// -------------------------
#define PIOS_DSM_MAX_DEVS 2
#define PIOS_DSM_NUM_INPUTS 12
// -------------------------
// Servo outputs
// -------------------------
#define PIOS_SERVO_UPDATE_HZ 50
#define PIOS_SERVOS_INITIAL_POSITION 0 /* dont want to start motors, have no pulse till settings loaded */
// --------------------------
// Timer controller settings
// --------------------------
#define PIOS_TIM_MAX_DEVS 6
// -------------------------
// ADC
// PIOS_ADC_PinGet(0) = Current sensor
// PIOS_ADC_PinGet(1) = Voltage sensor
// PIOS_ADC_PinGet(4) = VREF
// PIOS_ADC_PinGet(5) = Temperature sensor
// -------------------------
#define PIOS_DMA_PIN_CONFIG \
{ \
{ GPIOC, GPIO_Pin_1, ADC_Channel_11 }, \
{ GPIOC, GPIO_Pin_2, ADC_Channel_12 }, \
{ NULL, 0, ADC_Channel_Vrefint }, /* Voltage reference */ \
{ NULL, 0, ADC_Channel_TempSensor }, /* Temperature sensor */ \
}
/* we have to do all this to satisfy the PIOS_ADC_MAX_SAMPLES define in pios_adc.h */
/* which is annoying because this then determines the rate at which we generate buffer turnover events */
/* the objective here is to get enough buffer space to support 100Hz averaging rate */
#define PIOS_ADC_NUM_CHANNELS 4
#define PIOS_ADC_MAX_OVERSAMPLING 2
#define PIOS_ADC_USE_ADC2 0
#define PIOS_ADC_USE_TEMP_SENSOR
#define PIOS_ADC_TEMPERATURE_PIN 3
// -------------------------
// USB
// -------------------------
#define PIOS_USB_MAX_DEVS 1
#define PIOS_USB_ENABLED 1 /* Should remove all references to this */
#define PIOS_USB_HID_MAX_DEVS 1
#endif /* PIOS_BOARD_H */
/**
* @}
* @}
*/

View File

@ -0,0 +1,100 @@
/**
******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_USB_BOARD Board specific USB definitions
* @brief Board specific USB definitions
* @{
*
* @file pios_usb_board_data.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Board specific USB definitions
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "inc/pios_usb_board_data.h" /* struct usb_*, USB_* */
#include <pios_sys.h> /* PIOS_SYS_SerialNumberGet */
#include <pios_usbhook.h> /* PIOS_USBHOOK_* */
#include <pios_usb_util.h> /* PIOS_USB_UTIL_AsciiToUtf8 */
static const uint8_t usb_product_id[24] = {
sizeof(usb_product_id),
USB_DESC_TYPE_STRING,
'D', 0,
'i', 0,
's', 0,
'c', 0,
'o', 0,
'v', 0,
'e', 0,
'r', 0,
'y', 0,
'F', 0,
'4', 0,
};
static uint8_t usb_serial_number[2 + PIOS_SYS_SERIAL_NUM_ASCII_LEN * 2 + (sizeof(PIOS_USB_BOARD_SN_SUFFIX) - 1) * 2] = {
sizeof(usb_serial_number),
USB_DESC_TYPE_STRING,
};
static const struct usb_string_langid usb_lang_id = {
.bLength = sizeof(usb_lang_id),
.bDescriptorType = USB_DESC_TYPE_STRING,
.bLangID = htousbs(USB_LANGID_ENGLISH_US),
};
static const uint8_t usb_vendor_id[28] = {
sizeof(usb_vendor_id),
USB_DESC_TYPE_STRING,
'o', 0,
'p', 0,
'e', 0,
'n', 0,
'p', 0,
'i', 0,
'l', 0,
'o', 0,
't', 0,
'.', 0,
'o', 0,
'r', 0,
'g', 0
};
int32_t PIOS_USB_BOARD_DATA_Init(void)
{
/* Load device serial number into serial number string */
uint8_t sn[PIOS_SYS_SERIAL_NUM_ASCII_LEN + 1];
PIOS_SYS_SerialNumberGet((char *)sn);
/* Concatenate the device serial number and the appropriate suffix ("+BL" or "+FW") into the USB serial number */
uint8_t *utf8 = &(usb_serial_number[2]);
utf8 = PIOS_USB_UTIL_AsciiToUtf8(utf8, sn, PIOS_SYS_SERIAL_NUM_ASCII_LEN);
utf8 = PIOS_USB_UTIL_AsciiToUtf8(utf8, (uint8_t *)PIOS_USB_BOARD_SN_SUFFIX, sizeof(PIOS_USB_BOARD_SN_SUFFIX) - 1);
PIOS_USBHOOK_RegisterString(USB_STRING_DESC_PRODUCT, (uint8_t *)&usb_product_id, sizeof(usb_product_id));
PIOS_USBHOOK_RegisterString(USB_STRING_DESC_SERIAL, (uint8_t *)&usb_serial_number, sizeof(usb_serial_number));
PIOS_USBHOOK_RegisterString(USB_STRING_DESC_LANG, (uint8_t *)&usb_lang_id, sizeof(usb_lang_id));
PIOS_USBHOOK_RegisterString(USB_STRING_DESC_VENDOR, (uint8_t *)&usb_vendor_id, sizeof(usb_vendor_id));
return 0;
}

View File

@ -141,6 +141,10 @@ ifdef EE_BANK_BASE
BOARD_CDEFS += -DEE_BANK_BASE=$(EE_BANK_BASE)
BOARD_CDEFS += -DEE_BANK_SIZE=$(EE_BANK_SIZE)
endif
ifdef USER_EE_BANK_BASE
BOARD_CDEFS += -DUSER_EE_BANK_BASE=$(USER_EE_BANK_BASE)
BOARD_CDEFS += -DUSER_EE_BANK_SIZE=$(USER_EE_BANK_SIZE)
endif
CDEFS += $(BOARD_CDEFS)
ifeq ($(DEBUG), YES)