1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2024-12-01 09:24:10 +01:00

More moving.

git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@35 ebee16cc-31ac-478f-84a7-5cbb03baadba
This commit is contained in:
gussy 2009-12-01 14:29:55 +00:00 committed by gussy
parent 7f9cf71870
commit f1bfb2a238
10 changed files with 591 additions and 8 deletions

View File

@ -0,0 +1,72 @@
#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.
*----------------------------------------------------------*/
#define configUSE_PREEMPTION 1
#define configUSE_IDLE_HOOK 0
#define configUSE_TICK_HOOK 0
#define configCPU_CLOCK_HZ ( ( unsigned long ) 72000000 )
#define configTICK_RATE_HZ ( ( portTickType ) 1000 )
#define configMAX_PRIORITIES ( ( unsigned portBASE_TYPE ) 5 )
#define configMINIMAL_STACK_SIZE ( ( unsigned short ) 256 )
#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 10 * 1024 ) )
#define configMAX_TASK_NAME_LEN ( 16 )
#define configUSE_TRACE_FACILITY 0
#define configUSE_16_BIT_TICKS 0
#define configIDLE_SHOULD_YIELD 1
#define configUSE_MUTEXES 1
#define configUSE_RECURSIVE_MUTEXES 1
#define configUSE_COUNTING_SEMAPHORES 0
#define configUSE_ALTERNATIVE_API 0
#define configCHECK_FOR_STACK_OVERFLOW 0
#define configQUEUE_REGISTRY_SIZE 10
/* Co-routine definitions. */
#define configUSE_CO_ROUTINES 0
#define configMAX_CO_ROUTINE_PRIORITIES ( 2 )
/* Set the following definitions to 1 to include the API function, or zero
to exclude the API function. */
#define INCLUDE_vTaskPrioritySet 1
#define INCLUDE_uxTaskPriorityGet 1
#define INCLUDE_vTaskDelete 1
#define INCLUDE_vTaskCleanUpResources 0
#define INCLUDE_vTaskSuspend 1
#define INCLUDE_vTaskDelayUntil 1
#define INCLUDE_vTaskDelay 1
#define INCLUDE_xTaskGetSchedulerState 1
#define INCLUDE_xTaskGetCurrentTaskHandle 1
#define INCLUDE_uxTaskGetStackHighWaterMark 0
/* This is the raw value as per the Cortex-M3 NVIC. Values can be 255
(lowest) to 0 (1?) (highest). */
#define configKERNEL_INTERRUPT_PRIORITY 255
#define configMAX_SYSCALL_INTERRUPT_PRIORITY 191 /* equivalent to 0xb0, or priority 11. */
/* 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
#endif /* FREERTOS_CONFIG_H */

View File

@ -0,0 +1,213 @@
/**
******************************************************************************
*
* @file pios_board.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2009.
* @brief Defines board hardware for the OpenPilot Version 0.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
//------------------------
// Default File Settings
//------------------------
#define SETTINGS_FILE "Settings.ini"
//------------------------
// DMA Channels Used
//------------------------
/* Channel 1 - */
/* Channel 2 - SPI1 (SPI_SD_RX) */
/* Channel 3 - SPI1 (SPI_SD_TX) */
/* Channel 4 - */
/* Channel 5 - */
/* Channel 6 - */
/* Channel 7 - */
/* Channel 8 - */
/* Channel 9 - */
/* Channel 10 - */
/* Channel 11 - */
/* Channel 12 - */
//------------------------
// Leds Definition
//------------------------
#define LED1_GPIO_PORT GPIOC
#define LED1_GPIO_PIN GPIO_Pin_12
#define LED1_GPIO_CLK RCC_APB2Periph_GPIOC
#define LED2_GPIO_PORT GPIOC
#define LED2_GPIO_PIN GPIO_Pin_13
#define LED2_GPIO_CLK RCC_APB2Periph_GPIOC
#define NUM_LED 2
//------------------------
// I2C
//------------------------
#define I2C_GPIO_PORT GPIOB
#define I2C_SDA_PIN GPIO_Pin_11
#define I2C_SCL_PIN GPIO_Pin_10
//------------------------
// Onboard Pressure sensor
//------------------------
#define HP03D_XCLR_GPIO_PORT GPIOC
#define HP03D_XCLR_GPIO_PIN GPIO_Pin_15
#define HP03D_MCLK_GPIO_PORT GPIOA
#define HP03D_MCLK_GPIO_PIN GPIO_Pin_1
//-------------------------
// GPS UART
//-------------------------
#define GPS_UART USART2
#define GPS_BAUD 57600
#define GPS_GPIO_PORT GPIOA
#define GPS_RX_PIN GPIO_Pin_3
#define GPS_TX_PIN GPIO_Pin_2
#define GPS_REMAP_FUNC { }
#define GPS_IRQ_CHANNEL USART2_IRQn
#define GPS_IRQHANDLER_FUNC void USART2_IRQHandler(void)
#define GPS_CLK_FUNC RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE)
#define GPS_NVIC_PRIO IRQ_PRIO_HIGHEST
//-------------------------
// Telemetry radio UART
//-------------------------
#define TELEM_UART USART3
#define TELEM_BAUD 115200
#define TELEM_GPIO_PORT GPIOC
#define TELEM_RX_PIN GPIO_Pin_11
#define TELEM_TX_PIN GPIO_Pin_10
#define TELEM_REMAP_FUNC { GPIO_PinRemapConfig(GPIO_PartialRemap_USART3, ENABLE); }
#define TELEM_IRQ_CHANNEL USART3_IRQn
#define TELEM_IRQHANDLER_FUNC void USART3_IRQHandler(void)
#define TELEM_CLK_FUNC RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART3, ENABLE)
#define TELEM_NVIC_PRIO IRQ_PRIO_HIGHEST
//-------------------------
// AUXSER USART (available instead of RX5/RX6)
//-------------------------
#define AUX_UART_BAUD 19200
#define AUX_UART_UART USART1
#define AUX_UART_GPIO_PORT GPIOA
#define AUX_UART_RX_PIN GPIO_Pin_10
#define AUX_UART_TX_PIN GPIO_Pin_9
#define AUX_UART_REMAP_FUNC { }
#define AUX_UART_IRQ_CHANNEL USART1_IRQn
#define AUX_UART_IRQHANDLER_FUNC void USART1_IRQHandler(void)
#define AUX_UART_CLK_FUNC RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE)
#define AUX_UART_NVIC_PRIO IRQ_PRIO_HIGH
//-------------------------
// USART Serial Ports
//-------------------------
#define UART_NUM 3
#define UART_RX_BUFFER_SIZE 1024
#define UART_TX_BUFFER_SIZE 256
#define COM_DEBUG_PORT TELEM
//-------------------------
// Receiver PWM inputs
//-------------------------
#define RECEIVER1_GPIO_PORT GPIOB
#define RECEIVER1_PIN GPIO_Pin_2 // PB2
#define RECEIVER1_TIM_PORT TIM3
#define RECEIVER1_CH TIM_Channel_3 // TIM3_CH3
#define RECEIVER2_GPIO_PORT GPIOB
#define RECEIVER2_PIN GPIO_Pin_1 // PB1
#define RECEIVER2_TIM_PORT TIM3
#define RECEIVER2_CH TIM_Channel_4 // TIM3_CH4
#define RECEIVER3_GPIO_PORT GPIOA
#define RECEIVER3_PIN GPIO_Pin_8 // PA8
#define RECEIVER3_TIM_PORT TIM1
#define RECEIVER3_CH TIM_Channel_1 // TIM1_CH1
#define RECEIVER4_GPIO_PORT GPIOA
#define RECEIVER4_PIN GPIO_Pin_0 // PA0
#define RECEIVER4_TIM_PORT TIM5
#define RECEIVER4_CH TIM_Channel_1 // TIM5_CH1
#define RECEIVER5_GPIO_PORT GPIOA
#define RECEIVER5_PIN GPIO_Pin_10 // PA10
#define RECEIVER5_TIM_PORT TIM1
#define RECEIVER5_CH TIM_Channel_3 // TIM1_CH3
#define RECEIVER6_GPIO_PORT GPIOA
#define RECEIVER6_PIN GPIO_Pin_9 // PA9
#define RECEIVER6_TIM_PORT TIM1
#define RECEIVER6_CH TIM_Channel_2 // TIM1_CH2
/* Not used in v0.1 HW
#define RECEIVER7_GPIO_PORT GPIOB
#define RECEIVER7_PIN GPIO_Pin_4 // PB4
#define RECEIVER7_TIM_PORT TIM3
#define RECEIVER7_CH TIM_Channel_1 // TIM3_CH1
#define RECEIVER8_GPIO_PORT GPIOB
#define RECEIVER8_PIN GPIO_Pin_5 // PB5
#define RECEIVER8_TIM_PORT TIM3
#define RECEIVER8_CH TIM_Channel_2 // TIM3_CH2
*/
#define NUM_RECEIVER_INPUTS 6
//-------------------------
// Servo outputs
//-------------------------
#define SERVO1_4_PORT GPIOB
#define SERVO1_PIN GPIO_Pin_6
#define SERVO2_PIN GPIO_Pin_7
#define SERVO3_PIN GPIO_Pin_8
#define SERVO4_PIN GPIO_Pin_9
#define SERVO5_8_PORT GPIOC
#define SERVO5_PIN GPIO_Pin_6
#define SERVO6_PIN GPIO_Pin_7
#define SERVO7_PIN GPIO_Pin_8
#define SERVO8_PIN GPIO_Pin_9
#define NUM_SERVO_OUTPUTS 8
//-------------------------
// Leveler (analog inputs)
//-------------------------
#define LEVELER_GPIO_PORT GPIOC
#define LEVELER_Z_PIN GPIO_Pin_0 // ADC123_IN10
#define LEVELER_A_PIN GPIO_Pin_1 // ADC123_IN11
#define LEVELER_B_PIN GPIO_Pin_2 // ADC123_IN12
//-------------------------
// USB
//-------------------------
#define USB_ACC_GPIO_PORT GPIOC
#define USB_DETECT_PIN GPIO_Pin_4
#define USB_PULLUP_PIN GPIO_Pin_14
//-------------------------
// Master Clock
//-------------------------
#define MASTER_CLOCK 72000000
#define PERIPHERAL_CLOCK (MASTER_CLOCK/2)
//-------------------------
// Interrupt Priorities
//-------------------------
#define IRQ_PRIO_LOW 12 // lower than RTOS
#define IRQ_PRIO_MID 8 // higher than RTOS
#define IRQ_PRIO_HIGH 5 // for like SPI, AIN, I2C etc...
#define IRQ_PRIO_HIGHEST 4 // for UART etc...
#endif /* PIOS_BOARD_H */

View File

@ -0,0 +1,33 @@
/**
******************************************************************************
*
* @file pios_irq.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2009.
* @brief IRQ functions header.
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PIOS_IRQ_H
#define PIOS_IRQ_H
/* Public Functions */
extern int IRQDisable(void);
extern int IRQEnable(void);
#endif /* PIOS_IRQ_H */

View File

@ -0,0 +1,38 @@
/**
******************************************************************************
*
* @file pios_led.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2009.
* @brief LED functions header.
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PIOS_LED_H
#define PIOS_LED_H
/* Type Definitions */
typedef enum {LED1 = 0, LED2 = 1} LedTypeDef;
/* Public Functions */
extern void LED_INIT(void);
extern void LED_ON(LedTypeDef LED);
extern void LED_OFF(LedTypeDef LED);
extern void LED_TOGGLE(LedTypeDef LED);
#endif /* PIOS_LED_H */

View File

@ -0,0 +1,66 @@
/**
******************************************************************************
*
* @file pios_settings.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2009.
* @brief Settings functions header
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PIOS_SETTINGS_H
#define PIOS_SETTINGS_H
/* Default Values */
/* GPSUART Default Values */
#define GPS_BAUDRATE 19200
#define TELEM_BAUDRATE 19200
#define AUXUART_ENABLED 0
#define AUXUART_BAUDRATE 19200
/* Global types */
typedef struct {
uint32_t Baudrate;
} GPSSettingsTypeDef;
typedef struct {
uint32_t Baudrate;
} TelemSettingsTypeDef;
typedef struct {
bool Enabled;
uint32_t Baudrate;
} UARTSettingsTypeDef;
typedef struct {
GPSSettingsTypeDef GPS;
TelemSettingsTypeDef Telem;
UARTSettingsTypeDef AuxUART;
} SettingsTypeDef;
/*Global Variables */
extern SettingsTypeDef Settings;
/* Public Functions */
extern void LoadSettings(void);
extern void DumpSettings(USART_TypeDef* USARTx);
extern int CheckForSettingsFiles(void);
#endif /* PIOS_SETTINGS_H */

View File

@ -0,0 +1,32 @@
/**
******************************************************************************
*
* @file pios_sys.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2009.
* @brief System and hardware Init functions header.
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PIOS_SYS_H
#define PIOS_SYS_H
/* Public Functions */
extern void SysInit(void);
#endif /* PIOS_SYS_H */

View File

@ -0,0 +1,53 @@
/**
******************************************************************************
*
* @file pios_uart.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2009.
* @brief UART functions header.
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PIOS_UART_H
#define PIOS_UART_H
/* Global Types */
typedef enum {GPS = 0, TELEM = 1, AUX = 2} UARTNumTypeDef;
/* Public Functions */
extern void UARTInit(void);
extern void EnableAuxUART(void);
extern void DisableAuxUART(void);
extern void UARTChangeBaud(USART_TypeDef* USARTx, uint32_t Baud);
extern int UARTRxBufferFree(UARTNumTypeDef uart);
extern int UARTRxBufferUsed(UARTNumTypeDef uart);
extern int UARTRxBufferGet(UARTNumTypeDef uart);
extern int UARTRxBufferPeek(UARTNumTypeDef uart);
extern int UARTRxBufferPut(UARTNumTypeDef uart, uint8_t b);
extern int UARTTxBufferFree(UARTNumTypeDef uart);
extern int UARTTxBufferGet(UARTNumTypeDef uart);
extern int UARTTxBufferPutMoreNonBlocking(UARTNumTypeDef uart, uint8_t *buffer, uint16_t len);
extern int UARTTxBufferPutMore(UARTNumTypeDef uart, uint8_t *buffer, uint16_t len);
extern int UARTTxBufferPutNonBlocking(uint8_t uart, uint8_t b);
extern int UARTTxBufferPut(UARTNumTypeDef uart, uint8_t b);
#endif /* PIOS_UART_H */

View File

@ -0,0 +1,76 @@
/**
******************************************************************************
* @file Project/Template/stm32f10x_conf.h
* @author MCD Application Team
* @version V3.1.2
* @date 09/28/2009
* @brief Library configuration file.
******************************************************************************
* @copy
*
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE
* TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY
* DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING
* FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE
* CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*
* <h2><center>&copy; COPYRIGHT 2009 STMicroelectronics</center></h2>
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_CONF_H
#define __STM32F10x_CONF_H
/* Includes ------------------------------------------------------------------*/
/* Uncomment the line below to enable peripheral header file inclusion */
#include "stm32f10x_adc.h"
#include "stm32f10x_bkp.h"
/* #include "stm32f10x_can.h" */
#include "stm32f10x_crc.h"
#include "stm32f10x_dac.h"
/* #include "stm32f10x_dbgmcu.h" */
#include "stm32f10x_dma.h"
#include "stm32f10x_exti.h"
#include "stm32f10x_flash.h"
/* #include "stm32f10x_fsmc.h" */
#include "stm32f10x_gpio.h"
#include "stm32f10x_i2c.h"
/* #include "stm32f10x_iwdg.h" */
#include "stm32f10x_pwr.h"
#include "stm32f10x_rcc.h"
#include "stm32f10x_rtc.h"
/* #include "stm32f10x_sdio.h" */
#include "stm32f10x_spi.h"
#include "stm32f10x_tim.h"
#include "stm32f10x_usart.h"
/* #include "stm32f10x_wwdg.h" */
#include "misc.h" /* High level functions for NVIC and SysTick (add-on to CMSIS functions) */
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Uncomment the line below to expanse the "assert_param" macro in the
Standard Peripheral Library drivers code */
#define USE_FULL_ASSERT 1
/* Exported macro ------------------------------------------------------------*/
#ifdef USE_FULL_ASSERT
/**
* The assert_param macro is used for function's parameters check.
* \param[in] expr: If expr is false, it calls assert_failed function
* which reports the name of the source file and the source
* line number of the call that failed.
* If expr is true, it returns no value.
* \retval None
*/
#define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__))
/* Exported functions ------------------------------------------------------- */
extern void assert_failed(uint8_t* file, uint32_t line);
#else
#define assert_param(expr) ((void)0)
#endif /* USE_FULL_ASSERT */
#endif /* __STM32F10x_CONF_H */
/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/

View File

@ -36,7 +36,7 @@
/* STM32 Std Perf Lib */
#include <stm32f10x.h>
#include "STM32F10x/inc/stm32f10x_conf.h"
#include <stm32f10x_conf.h>
/* FatFS Includes */
#include <ff.h>
@ -46,15 +46,15 @@
#include <minIni.h>
/* PIOS Hardware Includes (STM32F10x) */
#include "STM32F10x/inc/pios_board.h"
#include "STM32F10x/inc/pios_sys.h"
#include "STM32F10x/inc/pios_settings.h"
#include "STM32F10x/inc/pios_led.h"
#include "STM32F10x/inc/pios_uart.h"
#include "STM32F10x/inc/pios_irq.h"
#include "inc/pios_board.h"
#include "inc/pios_sys.h"
#include "inc/pios_settings.h"
#include "inc/pios_led.h"
#include "inc/pios_uart.h"
#include "inc/pios_irq.h"
/* PIOS Hardware Includes (Common) */
#include "Common/inc/pios_com.h"
#include "inc/pios_com.h"
/* More added here as they get written */