mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2024-12-01 09:24:10 +01:00
Some Doxygen work and comments.
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@16 ebee16cc-31ac-478f-84a7-5cbb03baadba
This commit is contained in:
parent
5efc81f6c9
commit
845a4ff817
@ -65,13 +65,13 @@ int main()
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
/*******************************************************************************
|
/**
|
||||||
* Function Name : PiosMainTask
|
* Function Name : PiosMainTask
|
||||||
* Description : PIOS
|
* Description : PIOS
|
||||||
* Input : None
|
* Input : None
|
||||||
* Output : None
|
* Output : None
|
||||||
* Return : None
|
* Return : None
|
||||||
*******************************************************************************/
|
*/
|
||||||
void PiosMainTask( void *pvParameters )
|
void PiosMainTask( void *pvParameters )
|
||||||
{
|
{
|
||||||
|
|
||||||
@ -80,13 +80,13 @@ void PiosMainTask( void *pvParameters )
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/*******************************************************************************
|
/**
|
||||||
* Function Name : SensorTask
|
* Function Name : SensorTask
|
||||||
* Description : PIOS
|
* Description : PIOS
|
||||||
* Input : None
|
* Input : None
|
||||||
* Output : None
|
* Output : None
|
||||||
* Return : None
|
* Return : None
|
||||||
*******************************************************************************/
|
*/
|
||||||
void SensorTask( void *pvParameters )
|
void SensorTask( void *pvParameters )
|
||||||
{
|
{
|
||||||
|
|
||||||
|
@ -30,7 +30,7 @@
|
|||||||
#define PIOS_H
|
#define PIOS_H
|
||||||
|
|
||||||
|
|
||||||
/* C Header Files */
|
/* C Lib Includes */
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
|
|
||||||
@ -38,14 +38,14 @@
|
|||||||
#include <stm32f10x.h>
|
#include <stm32f10x.h>
|
||||||
#include <stm32f10x_conf.h>
|
#include <stm32f10x_conf.h>
|
||||||
|
|
||||||
/* FatFS Functions */
|
/* FatFS Includes */
|
||||||
#include <ff.h>
|
#include <ff.h>
|
||||||
#include <diskio.h>
|
#include <diskio.h>
|
||||||
|
|
||||||
/* minIni Functions */
|
/* minIni Includes */
|
||||||
#include <minIni.h>
|
#include <minIni.h>
|
||||||
|
|
||||||
/* Include PIOS Hardware Header Files */
|
/* PIOS Hardware Includes */
|
||||||
#include <pios_board.h>
|
#include <pios_board.h>
|
||||||
#include <pios_sys.h>
|
#include <pios_sys.h>
|
||||||
#include <pios_settings.h>
|
#include <pios_settings.h>
|
||||||
|
@ -44,7 +44,8 @@
|
|||||||
/* Channel 5 - */
|
/* Channel 5 - */
|
||||||
/* Channel 6 - */
|
/* Channel 6 - */
|
||||||
/* Channel 7 - */
|
/* Channel 7 - */
|
||||||
/* Channel 8 - */
|
/* Channel 8 - */
|
||||||
|
|
||||||
/* Channel 9 - */
|
/* Channel 9 - */
|
||||||
/* Channel 10 - */
|
/* Channel 10 - */
|
||||||
/* Channel 11 - */
|
/* Channel 11 - */
|
||||||
@ -53,18 +54,18 @@
|
|||||||
//------------------------
|
//------------------------
|
||||||
// Leds Definition
|
// Leds Definition
|
||||||
//------------------------
|
//------------------------
|
||||||
#define LED1_GPIO_PORT GPIOC
|
#define LED1_GPIO_PORT GPIOC
|
||||||
#define LED1_GPIO_PIN GPIO_Pin_12
|
#define LED1_GPIO_PIN GPIO_Pin_12
|
||||||
#define LED1_GPIO_CLK RCC_APB2Periph_GPIOC
|
#define LED1_GPIO_CLK RCC_APB2Periph_GPIOC
|
||||||
#define LED2_GPIO_PORT GPIOC
|
#define LED2_GPIO_PORT GPIOC
|
||||||
#define LED2_GPIO_PIN GPIO_Pin_13
|
#define LED2_GPIO_PIN GPIO_Pin_13
|
||||||
#define LED2_GPIO_CLK RCC_APB2Periph_GPIOC
|
#define LED2_GPIO_CLK RCC_APB2Periph_GPIOC
|
||||||
#define NUM_LED 2
|
#define NUM_LED 2
|
||||||
|
|
||||||
//------------------------
|
//------------------------
|
||||||
// I2C
|
// I2C
|
||||||
//------------------------
|
//------------------------
|
||||||
#define I2C_GPIO_PORT GPIOB
|
#define I2C_GPIO_PORT GPIOB
|
||||||
#define I2C_SDA_PIN GPIO_Pin_11
|
#define I2C_SDA_PIN GPIO_Pin_11
|
||||||
#define I2C_SCL_PIN GPIO_Pin_10
|
#define I2C_SCL_PIN GPIO_Pin_10
|
||||||
|
|
||||||
@ -72,143 +73,143 @@
|
|||||||
// Onboard Pressure sensor
|
// Onboard Pressure sensor
|
||||||
//------------------------
|
//------------------------
|
||||||
#define HP03D_XCLR_GPIO_PORT GPIOC
|
#define HP03D_XCLR_GPIO_PORT GPIOC
|
||||||
#define HP03D_XCLR_GPIO_PIN GPIO_Pin_15
|
#define HP03D_XCLR_GPIO_PIN GPIO_Pin_15
|
||||||
#define HP03D_MCLK_GPIO_PORT GPIOA
|
#define HP03D_MCLK_GPIO_PORT GPIOA
|
||||||
#define HP03D_MCLK_GPIO_PIN GPIO_Pin_1
|
#define HP03D_MCLK_GPIO_PIN GPIO_Pin_1
|
||||||
|
|
||||||
//-------------------------
|
//-------------------------
|
||||||
// GPS UART
|
// GPS UART
|
||||||
//-------------------------
|
//-------------------------
|
||||||
#define GPS_UART USART2
|
#define GPS_UART USART2
|
||||||
#define GPS_BAUD 57600
|
#define GPS_BAUD 57600
|
||||||
#define GPS_GPIO_PORT GPIOA
|
#define GPS_GPIO_PORT GPIOA
|
||||||
#define GPS_RX_PIN GPIO_Pin_3
|
#define GPS_RX_PIN GPIO_Pin_3
|
||||||
#define GPS_TX_PIN GPIO_Pin_2
|
#define GPS_TX_PIN GPIO_Pin_2
|
||||||
#define GPS_REMAP_FUNC { }
|
#define GPS_REMAP_FUNC { }
|
||||||
#define GPS_IRQ_CHANNEL USART2_IRQn
|
#define GPS_IRQ_CHANNEL USART2_IRQn
|
||||||
#define GPS_IRQHANDLER_FUNC void USART2_IRQHandler(void)
|
#define GPS_IRQHANDLER_FUNC void USART2_IRQHandler(void)
|
||||||
#define GPS_CLK_FUNC RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE)
|
#define GPS_CLK_FUNC RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE)
|
||||||
#define GPS_NVIC_PRIO IRQ_PRIO_HIGHEST
|
#define GPS_NVIC_PRIO IRQ_PRIO_HIGHEST
|
||||||
|
|
||||||
//-------------------------
|
//-------------------------
|
||||||
// Telemetry radio UART
|
// Telemetry radio UART
|
||||||
//-------------------------
|
//-------------------------
|
||||||
#define TELEM_UART USART3
|
#define TELEM_UART USART3
|
||||||
#define TELEM_BAUD 115200
|
#define TELEM_BAUD 115200
|
||||||
#define TELEM_GPIO_PORT GPIOC
|
#define TELEM_GPIO_PORT GPIOC
|
||||||
#define TELEM_RX_PIN GPIO_Pin_11
|
#define TELEM_RX_PIN GPIO_Pin_11
|
||||||
#define TELEM_TX_PIN GPIO_Pin_10
|
#define TELEM_TX_PIN GPIO_Pin_10
|
||||||
#define TELEM_REMAP_FUNC { GPIO_PinRemapConfig(GPIO_PartialRemap_USART3, ENABLE); }
|
#define TELEM_REMAP_FUNC { GPIO_PinRemapConfig(GPIO_PartialRemap_USART3, ENABLE); }
|
||||||
#define TELEM_IRQ_CHANNEL USART3_IRQn
|
#define TELEM_IRQ_CHANNEL USART3_IRQn
|
||||||
#define TELEM_IRQHANDLER_FUNC void USART3_IRQHandler(void)
|
#define TELEM_IRQHANDLER_FUNC void USART3_IRQHandler(void)
|
||||||
#define TELEM_CLK_FUNC RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART3, ENABLE)
|
#define TELEM_CLK_FUNC RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART3, ENABLE)
|
||||||
#define TELEM_NVIC_PRIO IRQ_PRIO_HIGHEST
|
#define TELEM_NVIC_PRIO IRQ_PRIO_HIGHEST
|
||||||
|
|
||||||
//-------------------------
|
//-------------------------
|
||||||
// AUXSER USART (available instead of RX5/RX6)
|
// AUXSER USART (available instead of RX5/RX6)
|
||||||
//-------------------------
|
//-------------------------
|
||||||
#define AUX_UART_BAUD 19200
|
#define AUX_UART_BAUD 19200
|
||||||
#define AUX_UART_UART USART1
|
#define AUX_UART_UART USART1
|
||||||
#define AUX_UART_GPIO_PORT GPIOA
|
#define AUX_UART_GPIO_PORT GPIOA
|
||||||
#define AUX_UART_RX_PIN GPIO_Pin_10
|
#define AUX_UART_RX_PIN GPIO_Pin_10
|
||||||
#define AUX_UART_TX_PIN GPIO_Pin_9
|
#define AUX_UART_TX_PIN GPIO_Pin_9
|
||||||
#define AUX_UART_REMAP_FUNC { }
|
#define AUX_UART_REMAP_FUNC { }
|
||||||
#define AUX_UART_IRQ_CHANNEL USART1_IRQn
|
#define AUX_UART_IRQ_CHANNEL USART1_IRQn
|
||||||
#define AUX_UART_IRQHANDLER_FUNC void USART1_IRQHandler(void)
|
#define AUX_UART_IRQHANDLER_FUNC void USART1_IRQHandler(void)
|
||||||
#define AUX_UART_CLK_FUNC RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE)
|
#define AUX_UART_CLK_FUNC RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE)
|
||||||
#define AUX_UART_NVIC_PRIO IRQ_PRIO_HIGH
|
#define AUX_UART_NVIC_PRIO IRQ_PRIO_HIGH
|
||||||
|
|
||||||
//-------------------------
|
//-------------------------
|
||||||
// USART Serial Ports
|
// USART Serial Ports
|
||||||
//-------------------------
|
//-------------------------
|
||||||
#define UART_NUM 3
|
#define UART_NUM 3
|
||||||
#define UART_RX_BUFFER_SIZE 128
|
#define UART_RX_BUFFER_SIZE 128
|
||||||
#define UART_TX_BUFFER_SIZE 128
|
#define UART_TX_BUFFER_SIZE 128
|
||||||
|
|
||||||
//-------------------------
|
//-------------------------
|
||||||
// Receiver PWM inputs
|
// Receiver PWM inputs
|
||||||
//-------------------------
|
//-------------------------
|
||||||
#define RECEIVER1_GPIO_PORT GPIOB
|
#define RECEIVER1_GPIO_PORT GPIOB
|
||||||
#define RECEIVER1_PIN GPIO_Pin_2 // PB2
|
#define RECEIVER1_PIN GPIO_Pin_2 // PB2
|
||||||
#define RECEIVER1_TIM_PORT TIM3
|
#define RECEIVER1_TIM_PORT TIM3
|
||||||
#define RECEIVER1_CH TIM_Channel_3 // TIM3_CH3
|
#define RECEIVER1_CH TIM_Channel_3 // TIM3_CH3
|
||||||
#define RECEIVER2_GPIO_PORT GPIOB
|
#define RECEIVER2_GPIO_PORT GPIOB
|
||||||
#define RECEIVER2_PIN GPIO_Pin_1 // PB1
|
#define RECEIVER2_PIN GPIO_Pin_1 // PB1
|
||||||
#define RECEIVER2_TIM_PORT TIM3
|
#define RECEIVER2_TIM_PORT TIM3
|
||||||
#define RECEIVER2_CH TIM_Channel_4 // TIM3_CH4
|
#define RECEIVER2_CH TIM_Channel_4 // TIM3_CH4
|
||||||
#define RECEIVER3_GPIO_PORT GPIOA
|
#define RECEIVER3_GPIO_PORT GPIOA
|
||||||
#define RECEIVER3_PIN GPIO_Pin_8 // PA8
|
#define RECEIVER3_PIN GPIO_Pin_8 // PA8
|
||||||
#define RECEIVER3_TIM_PORT TIM1
|
#define RECEIVER3_TIM_PORT TIM1
|
||||||
#define RECEIVER3_CH TIM_Channel_1 // TIM1_CH1
|
#define RECEIVER3_CH TIM_Channel_1 // TIM1_CH1
|
||||||
#define RECEIVER4_GPIO_PORT GPIOA
|
#define RECEIVER4_GPIO_PORT GPIOA
|
||||||
#define RECEIVER4_PIN GPIO_Pin_0 // PA0
|
#define RECEIVER4_PIN GPIO_Pin_0 // PA0
|
||||||
#define RECEIVER4_TIM_PORT TIM5
|
#define RECEIVER4_TIM_PORT TIM5
|
||||||
#define RECEIVER4_CH TIM_Channel_1 // TIM5_CH1
|
#define RECEIVER4_CH TIM_Channel_1 // TIM5_CH1
|
||||||
#define RECEIVER5_GPIO_PORT GPIOA
|
#define RECEIVER5_GPIO_PORT GPIOA
|
||||||
#define RECEIVER5_PIN GPIO_Pin_10 // PA10
|
#define RECEIVER5_PIN GPIO_Pin_10 // PA10
|
||||||
#define RECEIVER5_TIM_PORT TIM1
|
#define RECEIVER5_TIM_PORT TIM1
|
||||||
#define RECEIVER5_CH TIM_Channel_3 // TIM1_CH3
|
#define RECEIVER5_CH TIM_Channel_3 // TIM1_CH3
|
||||||
#define RECEIVER6_GPIO_PORT GPIOA
|
#define RECEIVER6_GPIO_PORT GPIOA
|
||||||
#define RECEIVER6_PIN GPIO_Pin_9 // PA9
|
#define RECEIVER6_PIN GPIO_Pin_9 // PA9
|
||||||
#define RECEIVER6_TIM_PORT TIM1
|
#define RECEIVER6_TIM_PORT TIM1
|
||||||
#define RECEIVER6_CH TIM_Channel_2 // TIM1_CH2
|
#define RECEIVER6_CH TIM_Channel_2 // TIM1_CH2
|
||||||
|
|
||||||
/* Not used in v1.2 HW
|
/* Not used in v1.2 HW
|
||||||
#define RECEIVER7_GPIO_PORT GPIOB
|
#define RECEIVER7_GPIO_PORT GPIOB
|
||||||
#define RECEIVER7_PIN GPIO_Pin_4 // PB4
|
#define RECEIVER7_PIN GPIO_Pin_4 // PB4
|
||||||
#define RECEIVER7_TIM_PORT TIM3
|
#define RECEIVER7_TIM_PORT TIM3
|
||||||
#define RECEIVER7_CH TIM_Channel_1 // TIM3_CH1
|
#define RECEIVER7_CH TIM_Channel_1 // TIM3_CH1
|
||||||
#define RECEIVER8_GPIO_PORT GPIOB
|
#define RECEIVER8_GPIO_PORT GPIOB
|
||||||
#define RECEIVER8_PIN GPIO_Pin_5 // PB5
|
#define RECEIVER8_PIN GPIO_Pin_5 // PB5
|
||||||
#define RECEIVER8_TIM_PORT TIM3
|
#define RECEIVER8_TIM_PORT TIM3
|
||||||
#define RECEIVER8_CH TIM_Channel_2 // TIM3_CH2
|
#define RECEIVER8_CH TIM_Channel_2 // TIM3_CH2
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define NUM_RECEIVER_INPUTS 6
|
#define NUM_RECEIVER_INPUTS 6
|
||||||
|
|
||||||
//-------------------------
|
//-------------------------
|
||||||
// Servo outputs
|
// Servo outputs
|
||||||
//-------------------------
|
//-------------------------
|
||||||
#define SERVO1_4_PORT GPIOB
|
#define SERVO1_4_PORT GPIOB
|
||||||
#define SERVO1_PIN GPIO_Pin_6
|
#define SERVO1_PIN GPIO_Pin_6
|
||||||
#define SERVO2_PIN GPIO_Pin_7
|
#define SERVO2_PIN GPIO_Pin_7
|
||||||
#define SERVO3_PIN GPIO_Pin_8
|
#define SERVO3_PIN GPIO_Pin_8
|
||||||
#define SERVO4_PIN GPIO_Pin_9
|
#define SERVO4_PIN GPIO_Pin_9
|
||||||
#define SERVO5_8_PORT GPIOC
|
#define SERVO5_8_PORT GPIOC
|
||||||
#define SERVO5_PIN GPIO_Pin_6
|
#define SERVO5_PIN GPIO_Pin_6
|
||||||
#define SERVO6_PIN GPIO_Pin_7
|
#define SERVO6_PIN GPIO_Pin_7
|
||||||
#define SERVO7_PIN GPIO_Pin_8
|
#define SERVO7_PIN GPIO_Pin_8
|
||||||
#define SERVO8_PIN GPIO_Pin_9
|
#define SERVO8_PIN GPIO_Pin_9
|
||||||
|
|
||||||
#define NUM_SERVO_OUTPUTS 8
|
#define NUM_SERVO_OUTPUTS 8
|
||||||
|
|
||||||
//-------------------------
|
//-------------------------
|
||||||
// Leveler (analog inputs)
|
// Leveler (analog inputs)
|
||||||
//-------------------------
|
//-------------------------
|
||||||
#define LEVELER_GPIO_PORT GPIOC
|
#define LEVELER_GPIO_PORT GPIOC
|
||||||
#define LEVELER_Z_PIN GPIO_Pin_0 // ADC123_IN10
|
#define LEVELER_Z_PIN GPIO_Pin_0 // ADC123_IN10
|
||||||
#define LEVELER_A_PIN GPIO_Pin_1 // ADC123_IN11
|
#define LEVELER_A_PIN GPIO_Pin_1 // ADC123_IN11
|
||||||
#define LEVELER_B_PIN GPIO_Pin_2 // ADC123_IN12
|
#define LEVELER_B_PIN GPIO_Pin_2 // ADC123_IN12
|
||||||
|
|
||||||
//-------------------------
|
//-------------------------
|
||||||
// USB
|
// USB
|
||||||
//-------------------------
|
//-------------------------
|
||||||
#define USB_ACC_GPIO_PORT GPIOC
|
#define USB_ACC_GPIO_PORT GPIOC
|
||||||
#define USB_DETECT_PIN GPIO_Pin_4
|
#define USB_DETECT_PIN GPIO_Pin_4
|
||||||
#define USB_PULLUP_PIN GPIO_Pin_14
|
#define USB_PULLUP_PIN GPIO_Pin_14
|
||||||
|
|
||||||
//-------------------------
|
//-------------------------
|
||||||
// Master Clock
|
// Master Clock
|
||||||
//-------------------------
|
//-------------------------
|
||||||
#define MASTER_CLOCK 72000000
|
#define MASTER_CLOCK 72000000
|
||||||
#define PERIPHERAL_CLOCK (MASTER_CLOCK/2)
|
#define PERIPHERAL_CLOCK (MASTER_CLOCK/2)
|
||||||
|
|
||||||
//-------------------------
|
//-------------------------
|
||||||
// Interrupt Priorities
|
// Interrupt Priorities
|
||||||
//-------------------------
|
//-------------------------
|
||||||
#define IRQ_PRIO_LOW 12 // lower than RTOS
|
#define IRQ_PRIO_LOW 12 // lower than RTOS
|
||||||
#define IRQ_PRIO_MID 8 // higher than RTOS
|
#define IRQ_PRIO_MID 8 // higher than RTOS
|
||||||
#define IRQ_PRIO_HIGH 5 // for like SPI, AIN, I2C etc...
|
#define IRQ_PRIO_HIGH 5 // for like SPI, AIN, I2C etc...
|
||||||
#define IRQ_PRIO_HIGHEST 4 // for UART etc...
|
#define IRQ_PRIO_HIGHEST 4 // for UART etc...
|
||||||
|
|
||||||
#endif /* PIOS_BOARD_H */
|
#endif /* PIOS_BOARD_H */
|
||||||
|
@ -30,11 +30,6 @@
|
|||||||
#include "pios.h"
|
#include "pios.h"
|
||||||
|
|
||||||
|
|
||||||
/* Public Function Prototypes */
|
|
||||||
int IRQDisable(void);
|
|
||||||
int IRQEnable(void);
|
|
||||||
|
|
||||||
|
|
||||||
/* Private Function Prototypes */
|
/* Private Function Prototypes */
|
||||||
|
|
||||||
|
|
||||||
@ -46,13 +41,13 @@ static unsigned int nested_ctr;
|
|||||||
static unsigned int prev_primask;
|
static unsigned int prev_primask;
|
||||||
|
|
||||||
|
|
||||||
/*******************************************************************************
|
/**
|
||||||
* Function Name : IRQDisable
|
* Function Name : IRQDisable
|
||||||
* Description : Disables all interrupts (nested)
|
* Description : Disables all interrupts (nested)
|
||||||
* Input : None
|
* Input : None
|
||||||
* Output : None
|
* Output : None
|
||||||
* Return : Zero on no error
|
* Return : Zero on no error
|
||||||
*******************************************************************************/
|
*/
|
||||||
int IRQDisable(void)
|
int IRQDisable(void)
|
||||||
{
|
{
|
||||||
/* Get current priority if nested level == 0 */
|
/* Get current priority if nested level == 0 */
|
||||||
@ -77,13 +72,13 @@ int IRQDisable(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
/*******************************************************************************
|
/**
|
||||||
* Function Name : IRQEnable
|
* Function Name : IRQEnable
|
||||||
* Description : Enables all interrupts (nested)
|
* Description : Enables all interrupts (nested)
|
||||||
* Input : None
|
* Input : None
|
||||||
* Output : None
|
* Output : None
|
||||||
* Return : Zero on no error, -1 on nesting error
|
* Return : Zero on no error, -1 on nesting error
|
||||||
*******************************************************************************/
|
*/
|
||||||
int IRQEnable(void)
|
int IRQEnable(void)
|
||||||
{
|
{
|
||||||
/* Check for nesting error */
|
/* Check for nesting error */
|
||||||
|
@ -30,13 +30,6 @@
|
|||||||
#include "pios.h"
|
#include "pios.h"
|
||||||
|
|
||||||
|
|
||||||
/* Public Function Prototypes */
|
|
||||||
void LED_INIT(void);
|
|
||||||
void LED_ON(LedTypeDef LEDNum);
|
|
||||||
void LED_OFF(LedTypeDef LEDNum);
|
|
||||||
void LED_TOGGLE(LedTypeDef LEDNum);
|
|
||||||
|
|
||||||
|
|
||||||
/* Private Function Prototypes */
|
/* Private Function Prototypes */
|
||||||
|
|
||||||
|
|
||||||
@ -46,13 +39,13 @@ const uint16_t LED_GPIO_PIN[NUM_LED] = {LED1_GPIO_PIN, LED2_GPIO_PIN};
|
|||||||
const uint32_t LED_GPIO_CLK[NUM_LED] = {LED1_GPIO_CLK, LED2_GPIO_CLK};
|
const uint32_t LED_GPIO_CLK[NUM_LED] = {LED1_GPIO_CLK, LED2_GPIO_CLK};
|
||||||
|
|
||||||
|
|
||||||
/*******************************************************************************
|
/**
|
||||||
* Function Name : LED_INIT
|
* Function Name : LED_INIT
|
||||||
* Description : Initialises all the LED's
|
* Description : Initialises all the LED's
|
||||||
* Input : None
|
* Input : None
|
||||||
* Output : None
|
* Output : None
|
||||||
* Return : None
|
* Return : None
|
||||||
*******************************************************************************/
|
*/
|
||||||
void LED_INIT(void)
|
void LED_INIT(void)
|
||||||
{
|
{
|
||||||
GPIO_InitTypeDef GPIO_InitStructure;
|
GPIO_InitTypeDef GPIO_InitStructure;
|
||||||
@ -67,39 +60,39 @@ void LED_INIT(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
/*******************************************************************************
|
/**
|
||||||
* Function Name : LED_ON
|
* Function Name : LED_ON
|
||||||
* Description : Turn on LED
|
* Description : Turn on LED
|
||||||
* Input : LED Number
|
* Input : LED Number
|
||||||
* Output : None
|
* Output : None
|
||||||
* Return : None
|
* Return : None
|
||||||
*******************************************************************************/
|
*/
|
||||||
void LED_ON(LedTypeDef LEDNum)
|
void LED_ON(LedTypeDef LEDNum)
|
||||||
{
|
{
|
||||||
LED_GPIO_PORT[LEDNum]->BSRR = LED_GPIO_PIN[LEDNum];
|
LED_GPIO_PORT[LEDNum]->BSRR = LED_GPIO_PIN[LEDNum];
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
/*******************************************************************************
|
/**
|
||||||
* Function Name : LED_OFF
|
* Function Name : LED_OFF
|
||||||
* Description : Turn off LED
|
* Description : Turn off LED
|
||||||
* Input : LED Number
|
* Input : LED Number
|
||||||
* Output : None
|
* Output : None
|
||||||
* Return : None
|
* Return : None
|
||||||
*******************************************************************************/
|
*/
|
||||||
void LED_OFF(LedTypeDef LEDNum)
|
void LED_OFF(LedTypeDef LEDNum)
|
||||||
{
|
{
|
||||||
LED_GPIO_PORT[LEDNum]->BRR = LED_GPIO_PIN[LEDNum];
|
LED_GPIO_PORT[LEDNum]->BRR = LED_GPIO_PIN[LEDNum];
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
/*******************************************************************************
|
/**
|
||||||
* Function Name : LED_TOGGLE
|
* Function Name : LED_TOGGLE
|
||||||
* Description : Turn on/off LED
|
* Description : Turn on/off LED
|
||||||
* Input : LED Number
|
* Input : LED Number
|
||||||
* Output : None
|
* Output : None
|
||||||
* Return : None
|
* Return : None
|
||||||
*******************************************************************************/
|
*/
|
||||||
void LED_TOGGLE(LedTypeDef LEDNum)
|
void LED_TOGGLE(LedTypeDef LEDNum)
|
||||||
{
|
{
|
||||||
LED_GPIO_PORT[LEDNum]->ODR ^= LED_GPIO_PIN[LEDNum];
|
LED_GPIO_PORT[LEDNum]->ODR ^= LED_GPIO_PIN[LEDNum];
|
||||||
|
@ -30,10 +30,6 @@
|
|||||||
#include "pios.h"
|
#include "pios.h"
|
||||||
|
|
||||||
|
|
||||||
/* Public Function Prototypes */
|
|
||||||
void LoadSettings(void);
|
|
||||||
|
|
||||||
|
|
||||||
/* Private Function Prototypes */
|
/* Private Function Prototypes */
|
||||||
|
|
||||||
|
|
||||||
@ -41,7 +37,7 @@ void LoadSettings(void);
|
|||||||
SettingsTypeDef Settings;
|
SettingsTypeDef Settings;
|
||||||
|
|
||||||
|
|
||||||
/*******************************************************************************
|
/**
|
||||||
* Function Name : LoadSettings
|
* Function Name : LoadSettings
|
||||||
* Description : Populate System global Vars into Structs using MinIni,
|
* Description : Populate System global Vars into Structs using MinIni,
|
||||||
* : defaults are also set here. Only function in the file
|
* : defaults are also set here. Only function in the file
|
||||||
@ -50,7 +46,7 @@ SettingsTypeDef Settings;
|
|||||||
* Input : None
|
* Input : None
|
||||||
* Output : None
|
* Output : None
|
||||||
* Return : None
|
* Return : None
|
||||||
*******************************************************************************/
|
*/
|
||||||
/* Value Reading: ini_getl("Section", "Key", (DefaultValue), IniFile); */
|
/* Value Reading: ini_getl("Section", "Key", (DefaultValue), IniFile); */
|
||||||
/* String Reading: ini_gets("Section", "Key", "DefaultValue", StrBuffer, sizearray(StrBuffer), IniFile); */
|
/* String Reading: ini_gets("Section", "Key", "DefaultValue", StrBuffer, sizearray(StrBuffer), IniFile); */
|
||||||
|
|
||||||
|
@ -30,10 +30,6 @@
|
|||||||
#include "pios.h"
|
#include "pios.h"
|
||||||
|
|
||||||
|
|
||||||
/* Public Function Prototypes */
|
|
||||||
void SysInit(void);
|
|
||||||
|
|
||||||
|
|
||||||
/* Private Function Prototypes */
|
/* Private Function Prototypes */
|
||||||
void NVIC_Configuration(void);
|
void NVIC_Configuration(void);
|
||||||
|
|
||||||
@ -42,13 +38,13 @@ void NVIC_Configuration(void);
|
|||||||
FATFS Fatfs[_DRIVES]; // File system object for each logical drive */
|
FATFS Fatfs[_DRIVES]; // File system object for each logical drive */
|
||||||
|
|
||||||
|
|
||||||
/*******************************************************************************
|
/**
|
||||||
* Function Name : SysInit
|
* Function Name : SysInit
|
||||||
* Description : Brings up the System and Initializes peripherals
|
* Description : Brings up the System and Initializes peripherals
|
||||||
* Input : None
|
* Input : None
|
||||||
* Output : None
|
* Output : None
|
||||||
* Return : None
|
* Return : None
|
||||||
*******************************************************************************/
|
*/
|
||||||
//TODO: Get these in the right order, settings need to be loaded ASAP
|
//TODO: Get these in the right order, settings need to be loaded ASAP
|
||||||
void SysInit(void)
|
void SysInit(void)
|
||||||
{
|
{
|
||||||
@ -76,26 +72,26 @@ void SysInit(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
/*******************************************************************************
|
/**
|
||||||
* Function Name : GPIO_Configuration
|
* Function Name : GPIO_Configuration
|
||||||
* Description : Configures base level GPIO ports.
|
* Description : Configures base level GPIO ports.
|
||||||
* Input : None
|
* Input : None
|
||||||
* Output : None
|
* Output : None
|
||||||
* Return : None
|
* Return : None
|
||||||
*******************************************************************************/
|
*/
|
||||||
void GPIO_Configuration(void)
|
void GPIO_Configuration(void)
|
||||||
{
|
{
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
/*******************************************************************************
|
/**
|
||||||
* Function Name : NVIC_Configuration
|
* Function Name : NVIC_Configuration
|
||||||
* Description : Configures Vector Table base location and SysTick
|
* Description : Configures Vector Table base location and SysTick
|
||||||
* Input : None
|
* Input : None
|
||||||
* Output : None
|
* Output : None
|
||||||
* Return : None
|
* Return : None
|
||||||
*******************************************************************************/
|
*/
|
||||||
void NVIC_Configuration(void)
|
void NVIC_Configuration(void)
|
||||||
{
|
{
|
||||||
/* Set the Vector Table base address as specified in .ld file */
|
/* Set the Vector Table base address as specified in .ld file */
|
||||||
|
@ -30,13 +30,6 @@
|
|||||||
#include "pios.h"
|
#include "pios.h"
|
||||||
|
|
||||||
|
|
||||||
/* Public Function Prototypes */
|
|
||||||
void UARTInit(void);
|
|
||||||
void EnableAuxUART(void);
|
|
||||||
void DisableAuxUART(void);
|
|
||||||
void UARTChangeBaud(USART_TypeDef* USARTx, uint32_t Baud);
|
|
||||||
|
|
||||||
|
|
||||||
/* Private Function Prototypes */
|
/* Private Function Prototypes */
|
||||||
|
|
||||||
|
|
||||||
@ -52,13 +45,13 @@ static volatile u8 tx_buffer_head[UART_NUM];
|
|||||||
static volatile u8 tx_buffer_size[UART_NUM];
|
static volatile u8 tx_buffer_size[UART_NUM];
|
||||||
|
|
||||||
|
|
||||||
/*******************************************************************************
|
/**
|
||||||
* Function Name : UARTInit
|
* Function Name : UARTInit
|
||||||
* Description : Initialise the GPS and TELEM onboard UARTs
|
* Description : Initialise the GPS and TELEM onboard UARTs
|
||||||
* Input : None
|
* Input : None
|
||||||
* Output : None
|
* Output : None
|
||||||
* Return : None
|
* Return : None
|
||||||
*******************************************************************************/
|
*/
|
||||||
void UARTInit(void)
|
void UARTInit(void)
|
||||||
{
|
{
|
||||||
GPIO_InitTypeDef GPIO_InitStructure;
|
GPIO_InitTypeDef GPIO_InitStructure;
|
||||||
@ -149,40 +142,40 @@ void UARTInit(void)
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
/*******************************************************************************
|
/**
|
||||||
* Function Name : EnableAuxUART
|
* Function Name : EnableAuxUART
|
||||||
* Description : Enables AUX UART at the expense of servo inputs
|
* Description : Enables AUX UART at the expense of servo inputs
|
||||||
* Input : None
|
* Input : None
|
||||||
* Output : None
|
* Output : None
|
||||||
* Return : None
|
* Return : None
|
||||||
*******************************************************************************/
|
*/
|
||||||
void EnableAuxUART(void)
|
void EnableAuxUART(void)
|
||||||
{
|
{
|
||||||
//Implement after servo inputs are implemented
|
//Implement after servo inputs are implemented
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
/*******************************************************************************
|
/**
|
||||||
* Function Name : DisableAuxUART
|
* Function Name : DisableAuxUART
|
||||||
* Description : Disables AUX UART reclaims two servo inputs
|
* Description : Disables AUX UART reclaims two servo inputs
|
||||||
* Input : None
|
* Input : None
|
||||||
* Output : None
|
* Output : None
|
||||||
* Return : None
|
* Return : None
|
||||||
*******************************************************************************/
|
*/
|
||||||
void DisableAuxUART(void)
|
void DisableAuxUART(void)
|
||||||
{
|
{
|
||||||
//Implement after servo inputs are implemented
|
//Implement after servo inputs are implemented
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
/*******************************************************************************
|
/**
|
||||||
* Function Name : UARTInit
|
* Function Name : UARTInit
|
||||||
* Description : Changes the baud rate of the USART peripherial without
|
* Description : Changes the baud rate of the USART peripherial without
|
||||||
* : re-initialising.
|
* : re-initialising.
|
||||||
* Input : USART to change, new baud rate
|
* Input : USART to change, new baud rate
|
||||||
* Output : None
|
* Output : None
|
||||||
* Return : None
|
* Return : None
|
||||||
*******************************************************************************/
|
*/
|
||||||
void UARTChangeBaud(USART_TypeDef* USARTx, uint32_t Baud)
|
void UARTChangeBaud(USART_TypeDef* USARTx, uint32_t Baud)
|
||||||
{
|
{
|
||||||
/* USART BRR Configuration */
|
/* USART BRR Configuration */
|
||||||
|
Loading…
Reference in New Issue
Block a user