mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2024-12-01 09:24:10 +01:00
Compiles now
This commit is contained in:
parent
0931a518d4
commit
0ce80e02f5
@ -55,7 +55,7 @@
|
|||||||
#define PIOS_INCLUDE_SPI
|
#define PIOS_INCLUDE_SPI
|
||||||
#define PIOS_INCLUDE_SYS
|
#define PIOS_INCLUDE_SYS
|
||||||
#define PIOS_INCLUDE_USART
|
#define PIOS_INCLUDE_USART
|
||||||
#define PIOS_INCLUDE_USB_HID
|
##define PIOS_INCLUDE_USB_HID
|
||||||
#define PIOS_INCLUDE_BMP085
|
#define PIOS_INCLUDE_BMP085
|
||||||
//#define PIOS_INCLUDE_HCSR04
|
//#define PIOS_INCLUDE_HCSR04
|
||||||
#define PIOS_INCLUDE_OPAHRS
|
#define PIOS_INCLUDE_OPAHRS
|
||||||
|
429
flight/PiOS/STM32F4xx/pios_tim.c
Normal file
429
flight/PiOS/STM32F4xx/pios_tim.c
Normal file
@ -0,0 +1,429 @@
|
|||||||
|
#include "pios.h"
|
||||||
|
|
||||||
|
#include "pios_tim.h"
|
||||||
|
#include "pios_tim_priv.h"
|
||||||
|
|
||||||
|
enum pios_tim_dev_magic {
|
||||||
|
PIOS_TIM_DEV_MAGIC = 0x87654098,
|
||||||
|
};
|
||||||
|
|
||||||
|
struct pios_tim_dev {
|
||||||
|
enum pios_tim_dev_magic magic;
|
||||||
|
|
||||||
|
const struct pios_tim_channel * channels;
|
||||||
|
uint8_t num_channels;
|
||||||
|
|
||||||
|
const struct pios_tim_callbacks * callbacks;
|
||||||
|
uint32_t context;
|
||||||
|
};
|
||||||
|
|
||||||
|
#if 0
|
||||||
|
static bool PIOS_TIM_validate(struct pios_tim_dev * tim_dev)
|
||||||
|
{
|
||||||
|
return (tim_dev->magic == PIOS_TIM_DEV_MAGIC);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(PIOS_INCLUDE_FREERTOS) && 0
|
||||||
|
static struct pios_tim_dev * PIOS_TIM_alloc(void)
|
||||||
|
{
|
||||||
|
struct pios_tim_dev * tim_dev;
|
||||||
|
|
||||||
|
tim_dev = (struct pios_tim_dev *)malloc(sizeof(*tim_dev));
|
||||||
|
if (!tim_dev) return(NULL);
|
||||||
|
|
||||||
|
tim_dev->magic = PIOS_TIM_DEV_MAGIC;
|
||||||
|
return(tim_dev);
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
static struct pios_tim_dev pios_tim_devs[PIOS_TIM_MAX_DEVS];
|
||||||
|
static uint8_t pios_tim_num_devs;
|
||||||
|
static struct pios_tim_dev * PIOS_TIM_alloc(void)
|
||||||
|
{
|
||||||
|
struct pios_tim_dev * tim_dev;
|
||||||
|
|
||||||
|
if (pios_tim_num_devs >= PIOS_TIM_MAX_DEVS) {
|
||||||
|
return (NULL);
|
||||||
|
}
|
||||||
|
|
||||||
|
tim_dev = &pios_tim_devs[pios_tim_num_devs++];
|
||||||
|
tim_dev->magic = PIOS_TIM_DEV_MAGIC;
|
||||||
|
|
||||||
|
return (tim_dev);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
int32_t PIOS_TIM_InitClock(const struct pios_tim_clock_cfg * cfg)
|
||||||
|
{
|
||||||
|
PIOS_DEBUG_Assert(cfg);
|
||||||
|
|
||||||
|
/* Enable appropriate clock to timer module */
|
||||||
|
switch((uint32_t) cfg->timer) {
|
||||||
|
case (uint32_t)TIM1:
|
||||||
|
RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1, ENABLE);
|
||||||
|
break;
|
||||||
|
case (uint32_t)TIM2:
|
||||||
|
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE);
|
||||||
|
break;
|
||||||
|
case (uint32_t)TIM3:
|
||||||
|
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE);
|
||||||
|
break;
|
||||||
|
case (uint32_t)TIM4:
|
||||||
|
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM4, ENABLE);
|
||||||
|
break;
|
||||||
|
#ifdef STM32F10X_HD
|
||||||
|
case (uint32_t)TIM5:
|
||||||
|
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM5, ENABLE);
|
||||||
|
break;
|
||||||
|
case (uint32_t)TIM6:
|
||||||
|
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM6, ENABLE);
|
||||||
|
break;
|
||||||
|
case (uint32_t)TIM7:
|
||||||
|
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM7, ENABLE);
|
||||||
|
break;
|
||||||
|
case (uint32_t)TIM8:
|
||||||
|
RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM8, ENABLE);
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Configure the dividers for this timer */
|
||||||
|
TIM_TimeBaseInit(cfg->timer, cfg->time_base_init);
|
||||||
|
|
||||||
|
/* Configure internal timer clocks */
|
||||||
|
TIM_InternalClockConfig(cfg->timer);
|
||||||
|
|
||||||
|
/* Enable timers */
|
||||||
|
TIM_Cmd(cfg->timer, ENABLE);
|
||||||
|
|
||||||
|
/* Enable Interrupts */
|
||||||
|
NVIC_Init(&cfg->irq.init);
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
int32_t PIOS_TIM_InitChannels(uint32_t * tim_id, const struct pios_tim_channel * channels, uint8_t num_channels, const struct pios_tim_callbacks * callbacks, uint32_t context)
|
||||||
|
{
|
||||||
|
PIOS_Assert(channels);
|
||||||
|
PIOS_Assert(num_channels);
|
||||||
|
|
||||||
|
struct pios_tim_dev * tim_dev;
|
||||||
|
tim_dev = (struct pios_tim_dev *) PIOS_TIM_alloc();
|
||||||
|
if (!tim_dev) goto out_fail;
|
||||||
|
|
||||||
|
/* Bind the configuration to the device instance */
|
||||||
|
tim_dev->channels = channels;
|
||||||
|
tim_dev->num_channels = num_channels;
|
||||||
|
tim_dev->callbacks = callbacks;
|
||||||
|
tim_dev->context = context;
|
||||||
|
|
||||||
|
/* Configure the pins */
|
||||||
|
for (uint8_t i = 0; i < num_channels; i++) {
|
||||||
|
const struct pios_tim_channel * chan = &(channels[i]);
|
||||||
|
|
||||||
|
/* Enable the peripheral clock for the GPIO */
|
||||||
|
/* switch ((uint32_t)chan->pin.gpio) {
|
||||||
|
case (uint32_t) GPIOA:
|
||||||
|
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
|
||||||
|
break;
|
||||||
|
case (uint32_t) GPIOB:
|
||||||
|
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE);
|
||||||
|
break;
|
||||||
|
case (uint32_t) GPIOC:
|
||||||
|
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE);
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
PIOS_Assert(0);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
*/ // commented out for now as f4 starts all clocks
|
||||||
|
GPIO_Init(chan->pin.gpio, &chan->pin.init);
|
||||||
|
|
||||||
|
// F4 remaps pins differently
|
||||||
|
/* if (chan->remap) {
|
||||||
|
GPIO_PinRemapConfig(chan->remap, ENABLE);
|
||||||
|
} */
|
||||||
|
}
|
||||||
|
|
||||||
|
*tim_id = (uint32_t)tim_dev;
|
||||||
|
|
||||||
|
return(0);
|
||||||
|
|
||||||
|
out_fail:
|
||||||
|
return(-1);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void PIOS_TIM_generic_irq_handler(TIM_TypeDef * timer)
|
||||||
|
{
|
||||||
|
/* Iterate over all registered clients of the TIM layer to find channels on this timer */
|
||||||
|
for (uint8_t i = 0; i < pios_tim_num_devs; i++) {
|
||||||
|
const struct pios_tim_dev * tim_dev = &pios_tim_devs[i];
|
||||||
|
|
||||||
|
if (!tim_dev->channels || tim_dev->num_channels == 0) {
|
||||||
|
/* No channels to process on this client */
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Check for an overflow event on this timer */
|
||||||
|
bool overflow_event;
|
||||||
|
uint16_t overflow_count;
|
||||||
|
if (TIM_GetITStatus(timer, TIM_IT_Update) == SET) {
|
||||||
|
TIM_ClearITPendingBit(timer, TIM_IT_Update);
|
||||||
|
overflow_count = timer->ARR;
|
||||||
|
overflow_event = true;
|
||||||
|
} else {
|
||||||
|
overflow_count = 0;
|
||||||
|
overflow_event = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
for (uint8_t j = 0; j < tim_dev->num_channels; j++) {
|
||||||
|
const struct pios_tim_channel * chan = &tim_dev->channels[j];
|
||||||
|
|
||||||
|
if (chan->timer != timer) {
|
||||||
|
/* channel is not on this timer */
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Figure out which interrupt bit we should be looking at */
|
||||||
|
uint16_t timer_it;
|
||||||
|
switch (chan->timer_chan) {
|
||||||
|
case TIM_Channel_1:
|
||||||
|
timer_it = TIM_IT_CC1;
|
||||||
|
break;
|
||||||
|
case TIM_Channel_2:
|
||||||
|
timer_it = TIM_IT_CC2;
|
||||||
|
break;
|
||||||
|
case TIM_Channel_3:
|
||||||
|
timer_it = TIM_IT_CC3;
|
||||||
|
break;
|
||||||
|
case TIM_Channel_4:
|
||||||
|
timer_it = TIM_IT_CC4;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
PIOS_Assert(0);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool edge_event;
|
||||||
|
uint16_t edge_count;
|
||||||
|
if (TIM_GetITStatus(chan->timer, timer_it) == SET) {
|
||||||
|
TIM_ClearITPendingBit(chan->timer, timer_it);
|
||||||
|
|
||||||
|
/* Read the current counter */
|
||||||
|
switch(chan->timer_chan) {
|
||||||
|
case TIM_Channel_1:
|
||||||
|
edge_count = TIM_GetCapture1(chan->timer);
|
||||||
|
break;
|
||||||
|
case TIM_Channel_2:
|
||||||
|
edge_count = TIM_GetCapture2(chan->timer);
|
||||||
|
break;
|
||||||
|
case TIM_Channel_3:
|
||||||
|
edge_count = TIM_GetCapture3(chan->timer);
|
||||||
|
break;
|
||||||
|
case TIM_Channel_4:
|
||||||
|
edge_count = TIM_GetCapture4(chan->timer);
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
PIOS_Assert(0);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
edge_event = true;
|
||||||
|
} else {
|
||||||
|
edge_event = false;
|
||||||
|
edge_count = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!tim_dev->callbacks) {
|
||||||
|
/* No callbacks registered, we're done with this channel */
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Generate the appropriate callbacks */
|
||||||
|
if (overflow_event & edge_event) {
|
||||||
|
/*
|
||||||
|
* When both edge and overflow happen in the same interrupt, we
|
||||||
|
* need a heuristic to determine the order of the edge and overflow
|
||||||
|
* events so that the callbacks happen in the right order. If we
|
||||||
|
* get the order wrong, our pulse width calculations could be off by up
|
||||||
|
* to ARR ticks. That could be bad.
|
||||||
|
*
|
||||||
|
* Heuristic: If the edge_count is < 16 ticks above zero then we assume the
|
||||||
|
* edge happened just after the overflow.
|
||||||
|
*/
|
||||||
|
|
||||||
|
if (edge_count < 16) {
|
||||||
|
/* Call the overflow callback first */
|
||||||
|
if (tim_dev->callbacks->overflow) {
|
||||||
|
(*tim_dev->callbacks->overflow)((uint32_t)tim_dev,
|
||||||
|
tim_dev->context,
|
||||||
|
j,
|
||||||
|
overflow_count);
|
||||||
|
}
|
||||||
|
/* Call the edge callback second */
|
||||||
|
if (tim_dev->callbacks->edge) {
|
||||||
|
(*tim_dev->callbacks->edge)((uint32_t)tim_dev,
|
||||||
|
tim_dev->context,
|
||||||
|
j,
|
||||||
|
edge_count);
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
/* Call the edge callback first */
|
||||||
|
if (tim_dev->callbacks->edge) {
|
||||||
|
(*tim_dev->callbacks->edge)((uint32_t)tim_dev,
|
||||||
|
tim_dev->context,
|
||||||
|
j,
|
||||||
|
edge_count);
|
||||||
|
}
|
||||||
|
/* Call the overflow callback second */
|
||||||
|
if (tim_dev->callbacks->overflow) {
|
||||||
|
(*tim_dev->callbacks->overflow)((uint32_t)tim_dev,
|
||||||
|
tim_dev->context,
|
||||||
|
j,
|
||||||
|
overflow_count);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
} else if (overflow_event && tim_dev->callbacks->overflow) {
|
||||||
|
(*tim_dev->callbacks->overflow)((uint32_t)tim_dev,
|
||||||
|
tim_dev->context,
|
||||||
|
j,
|
||||||
|
overflow_count);
|
||||||
|
} else if (edge_event && tim_dev->callbacks->edge) {
|
||||||
|
(*tim_dev->callbacks->edge)((uint32_t)tim_dev,
|
||||||
|
tim_dev->context,
|
||||||
|
j,
|
||||||
|
edge_count);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#if 0
|
||||||
|
uint16_t val = 0;
|
||||||
|
for(uint8_t i = 0; i < pios_pwm_cfg.num_channels; i++) {
|
||||||
|
struct pios_pwm_channel channel = pios_pwm_cfg.channels[i];
|
||||||
|
if ((channel.timer == timer) && (TIM_GetITStatus(channel.timer, channel.ccr) == SET)) {
|
||||||
|
|
||||||
|
TIM_ClearITPendingBit(channel.timer, channel.ccr);
|
||||||
|
|
||||||
|
switch(channel.channel) {
|
||||||
|
case TIM_Channel_1:
|
||||||
|
val = TIM_GetCapture1(channel.timer);
|
||||||
|
break;
|
||||||
|
case TIM_Channel_2:
|
||||||
|
val = TIM_GetCapture2(channel.timer);
|
||||||
|
break;
|
||||||
|
case TIM_Channel_3:
|
||||||
|
val = TIM_GetCapture3(channel.timer);
|
||||||
|
break;
|
||||||
|
case TIM_Channel_4:
|
||||||
|
val = TIM_GetCapture4(channel.timer);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (CaptureState[i] == 0) {
|
||||||
|
RiseValue[i] = val;
|
||||||
|
} else {
|
||||||
|
FallValue[i] = val;
|
||||||
|
}
|
||||||
|
|
||||||
|
// flip state machine and capture value here
|
||||||
|
/* Simple rise or fall state machine */
|
||||||
|
TIM_ICInitTypeDef TIM_ICInitStructure = pios_pwm_cfg.tim_ic_init;
|
||||||
|
if (CaptureState[i] == 0) {
|
||||||
|
/* Switch states */
|
||||||
|
CaptureState[i] = 1;
|
||||||
|
|
||||||
|
/* Switch polarity of input capture */
|
||||||
|
TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Falling;
|
||||||
|
TIM_ICInitStructure.TIM_Channel = channel.channel;
|
||||||
|
TIM_ICInit(channel.timer, &TIM_ICInitStructure);
|
||||||
|
} else {
|
||||||
|
/* Capture computation */
|
||||||
|
if (FallValue[i] > RiseValue[i]) {
|
||||||
|
CaptureValue[i] = (FallValue[i] - RiseValue[i]);
|
||||||
|
} else {
|
||||||
|
CaptureValue[i] = ((channel.timer->ARR - RiseValue[i]) + FallValue[i]);
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Switch states */
|
||||||
|
CaptureState[i] = 0;
|
||||||
|
|
||||||
|
/* Increase supervisor counter */
|
||||||
|
CapCounter[i]++;
|
||||||
|
|
||||||
|
/* Switch polarity of input capture */
|
||||||
|
TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Rising;
|
||||||
|
TIM_ICInitStructure.TIM_Channel = channel.channel;
|
||||||
|
TIM_ICInit(channel.timer, &TIM_ICInitStructure);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* Bind Interrupt Handlers
|
||||||
|
*
|
||||||
|
* Map all valid TIM IRQs to the common interrupt handler
|
||||||
|
* and give it enough context to properly demux the various timers
|
||||||
|
*/
|
||||||
|
void TIM1_UP_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_1_UP_irq_handler")));
|
||||||
|
static void PIOS_TIM_1_UP_irq_handler (void)
|
||||||
|
{
|
||||||
|
PIOS_TIM_generic_irq_handler (TIM1);
|
||||||
|
}
|
||||||
|
|
||||||
|
void TIM1_CC_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_1_CC_irq_handler")));
|
||||||
|
static void PIOS_TIM_1_CC_irq_handler (void)
|
||||||
|
{
|
||||||
|
PIOS_TIM_generic_irq_handler (TIM1);
|
||||||
|
}
|
||||||
|
|
||||||
|
void TIM2_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_2_irq_handler")));
|
||||||
|
static void PIOS_TIM_2_irq_handler (void)
|
||||||
|
{
|
||||||
|
PIOS_TIM_generic_irq_handler (TIM2);
|
||||||
|
}
|
||||||
|
|
||||||
|
void TIM3_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_3_irq_handler")));
|
||||||
|
static void PIOS_TIM_3_irq_handler (void)
|
||||||
|
{
|
||||||
|
PIOS_TIM_generic_irq_handler (TIM3);
|
||||||
|
}
|
||||||
|
|
||||||
|
void TIM4_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_4_irq_handler")));
|
||||||
|
static void PIOS_TIM_4_irq_handler (void)
|
||||||
|
{
|
||||||
|
PIOS_TIM_generic_irq_handler (TIM4);
|
||||||
|
}
|
||||||
|
|
||||||
|
void TIM5_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_5_irq_handler")));
|
||||||
|
static void PIOS_TIM_5_irq_handler (void)
|
||||||
|
{
|
||||||
|
PIOS_TIM_generic_irq_handler (TIM5);
|
||||||
|
}
|
||||||
|
|
||||||
|
void TIM6_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_6_irq_handler")));
|
||||||
|
static void PIOS_TIM_6_irq_handler (void)
|
||||||
|
{
|
||||||
|
PIOS_TIM_generic_irq_handler (TIM6);
|
||||||
|
}
|
||||||
|
|
||||||
|
void TIM7_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_7_irq_handler")));
|
||||||
|
static void PIOS_TIM_7_irq_handler (void)
|
||||||
|
{
|
||||||
|
PIOS_TIM_generic_irq_handler (TIM7);
|
||||||
|
}
|
||||||
|
|
||||||
|
void TIM8_UP_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_8_UP_irq_handler")));
|
||||||
|
static void PIOS_TIM_8_UP_irq_handler (void)
|
||||||
|
{
|
||||||
|
PIOS_TIM_generic_irq_handler (TIM8);
|
||||||
|
}
|
||||||
|
|
||||||
|
void TIM8_CC_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_8_CC_irq_handler")));
|
||||||
|
static void PIOS_TIM_8_CC_irq_handler (void)
|
||||||
|
{
|
||||||
|
PIOS_TIM_generic_irq_handler (TIM8);
|
||||||
|
}
|
||||||
|
|
@ -208,23 +208,8 @@
|
|||||||
6560A38A13EE26B700105DA5 /* pios_wdg.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_wdg.c; sourceTree = "<group>"; };
|
6560A38A13EE26B700105DA5 /* pios_wdg.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_wdg.c; sourceTree = "<group>"; };
|
||||||
6560A38B13EE26B700105DA5 /* startup_stm32f2xx.S */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.asm; path = startup_stm32f2xx.S; sourceTree = "<group>"; };
|
6560A38B13EE26B700105DA5 /* startup_stm32f2xx.S */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.asm; path = startup_stm32f2xx.S; sourceTree = "<group>"; };
|
||||||
6560A38D13EE26B700105DA5 /* vectors_stm32f2xx.S */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.asm; path = vectors_stm32f2xx.S; sourceTree = "<group>"; };
|
6560A38D13EE26B700105DA5 /* vectors_stm32f2xx.S */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.asm; path = vectors_stm32f2xx.S; sourceTree = "<group>"; };
|
||||||
6560A38E13EE270C00105DA5 /* link_STM3210E_INS_BL_sections.ld */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = link_STM3210E_INS_BL_sections.ld; sourceTree = "<group>"; };
|
|
||||||
6560A38F13EE270C00105DA5 /* link_STM3210E_INS_memory.ld */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = link_STM3210E_INS_memory.ld; sourceTree = "<group>"; };
|
|
||||||
6560A39013EE270C00105DA5 /* link_STM3210E_INS_sections.ld */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = link_STM3210E_INS_sections.ld; sourceTree = "<group>"; };
|
|
||||||
6560A39113EE270C00105DA5 /* link_STM3210E_OP_BL_sections.ld */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = link_STM3210E_OP_BL_sections.ld; sourceTree = "<group>"; };
|
|
||||||
6560A39213EE270C00105DA5 /* link_STM3210E_OP_memory.ld */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = link_STM3210E_OP_memory.ld; sourceTree = "<group>"; };
|
|
||||||
6560A39313EE270C00105DA5 /* link_STM3210E_OP_sections.ld */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = link_STM3210E_OP_sections.ld; sourceTree = "<group>"; };
|
|
||||||
6560A39413EE270C00105DA5 /* link_STM32103CB_AHRS_BL_sections.ld */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = link_STM32103CB_AHRS_BL_sections.ld; sourceTree = "<group>"; };
|
|
||||||
6560A39513EE270C00105DA5 /* link_STM32103CB_AHRS_memory.ld */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = link_STM32103CB_AHRS_memory.ld; sourceTree = "<group>"; };
|
|
||||||
6560A39613EE270C00105DA5 /* link_STM32103CB_AHRS_sections.ld */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = link_STM32103CB_AHRS_sections.ld; sourceTree = "<group>"; };
|
|
||||||
6560A39713EE270C00105DA5 /* link_STM32103CB_CC_Rev1_BL_sections.ld */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = link_STM32103CB_CC_Rev1_BL_sections.ld; sourceTree = "<group>"; };
|
|
||||||
6560A39813EE270C00105DA5 /* link_STM32103CB_PIPXTREME_BL_sections.ld */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = link_STM32103CB_PIPXTREME_BL_sections.ld; sourceTree = "<group>"; };
|
|
||||||
6560A39913EE270C00105DA5 /* link_STM32103CB_PIPXTREME_memory.ld */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = link_STM32103CB_PIPXTREME_memory.ld; sourceTree = "<group>"; };
|
|
||||||
6560A39A13EE270C00105DA5 /* link_STM32103CB_PIPXTREME_sections.ld */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = link_STM32103CB_PIPXTREME_sections.ld; sourceTree = "<group>"; };
|
|
||||||
6560A39B13EE270C00105DA5 /* startup_stm32f10x_HD_OP.S */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.asm; path = startup_stm32f10x_HD_OP.S; sourceTree = "<group>"; };
|
6560A39B13EE270C00105DA5 /* startup_stm32f10x_HD_OP.S */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.asm; path = startup_stm32f10x_HD_OP.S; sourceTree = "<group>"; };
|
||||||
6560A39C13EE270C00105DA5 /* startup_stm32f10x_MD_CC.S */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.asm; path = startup_stm32f10x_MD_CC.S; sourceTree = "<group>"; };
|
6560A39C13EE270C00105DA5 /* startup_stm32f10x_MD_CC.S */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.asm; path = startup_stm32f10x_MD_CC.S; sourceTree = "<group>"; };
|
||||||
6560A39D13EE277E00105DA5 /* pios_iap.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_iap.c; sourceTree = "<group>"; };
|
|
||||||
6560A39E13EE277E00105DA5 /* pios_sbus.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_sbus.c; sourceTree = "<group>"; };
|
|
||||||
6560A3A013EE2E8B00105DA5 /* ahrs_slave_test.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = ahrs_slave_test.c; path = INS/ahrs_slave_test.c; sourceTree = "<group>"; };
|
6560A3A013EE2E8B00105DA5 /* ahrs_slave_test.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = ahrs_slave_test.c; path = INS/ahrs_slave_test.c; sourceTree = "<group>"; };
|
||||||
6560A3A113EE2E8B00105DA5 /* ahrs_spi_program_master.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = ahrs_spi_program_master.c; path = INS/ahrs_spi_program_master.c; sourceTree = "<group>"; };
|
6560A3A113EE2E8B00105DA5 /* ahrs_spi_program_master.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = ahrs_spi_program_master.c; path = INS/ahrs_spi_program_master.c; sourceTree = "<group>"; };
|
||||||
6560A3A213EE2E8B00105DA5 /* ahrs_spi_program_slave.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = ahrs_spi_program_slave.c; path = INS/ahrs_spi_program_slave.c; sourceTree = "<group>"; };
|
6560A3A213EE2E8B00105DA5 /* ahrs_spi_program_slave.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = ahrs_spi_program_slave.c; path = INS/ahrs_spi_program_slave.c; sourceTree = "<group>"; };
|
||||||
@ -276,6 +261,32 @@
|
|||||||
6589A983131DE24F006BD67C /* taskmonitor.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = taskmonitor.c; sourceTree = "<group>"; };
|
6589A983131DE24F006BD67C /* taskmonitor.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = taskmonitor.c; sourceTree = "<group>"; };
|
||||||
6589A9DB131DEE76006BD67C /* pios_rtc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_rtc.c; sourceTree = "<group>"; };
|
6589A9DB131DEE76006BD67C /* pios_rtc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_rtc.c; sourceTree = "<group>"; };
|
||||||
6589A9E2131DF1C7006BD67C /* pios_rtc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_rtc.h; sourceTree = "<group>"; };
|
6589A9E2131DF1C7006BD67C /* pios_rtc.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_rtc.h; sourceTree = "<group>"; };
|
||||||
|
65904E40146128A500FD9482 /* .Makefile.swp */ = {isa = PBXFileReference; lastKnownFileType = file; path = .Makefile.swp; sourceTree = "<group>"; };
|
||||||
|
65904E42146128A500FD9482 /* ahrs_timer.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ahrs_timer.h; sourceTree = "<group>"; };
|
||||||
|
65904E43146128A500FD9482 /* ins.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ins.h; sourceTree = "<group>"; };
|
||||||
|
65904E44146128A500FD9482 /* ins_fsm.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ins_fsm.h; sourceTree = "<group>"; };
|
||||||
|
65904E45146128A500FD9482 /* insgps.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = insgps.h; sourceTree = "<group>"; };
|
||||||
|
65904E46146128A500FD9482 /* insgps_helper.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = insgps_helper.h; sourceTree = "<group>"; };
|
||||||
|
65904E47146128A500FD9482 /* ins.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = ins.c; sourceTree = "<group>"; };
|
||||||
|
65904E48146128A500FD9482 /* insgps13state.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = insgps13state.c; sourceTree = "<group>"; };
|
||||||
|
65904E49146128A500FD9482 /* insgps16state.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = insgps16state.c; sourceTree = "<group>"; };
|
||||||
|
65904E4A146128A500FD9482 /* insgps_helper.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = insgps_helper.c; sourceTree = "<group>"; };
|
||||||
|
65904E4B146128A500FD9482 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = "<group>"; };
|
||||||
|
65904E4D146128A500FD9482 /* alarms.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = alarms.c; sourceTree = "<group>"; };
|
||||||
|
65904E4E146128A500FD9482 /* cm3_fault_handlers.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = cm3_fault_handlers.c; sourceTree = "<group>"; };
|
||||||
|
65904E4F146128A500FD9482 /* dcc_stdio.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = dcc_stdio.c; sourceTree = "<group>"; };
|
||||||
|
65904E51146128A500FD9482 /* alarms.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = alarms.h; sourceTree = "<group>"; };
|
||||||
|
65904E52146128A500FD9482 /* dcc_stdio.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = dcc_stdio.h; sourceTree = "<group>"; };
|
||||||
|
65904E53146128A500FD9482 /* FreeRTOSConfig.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = FreeRTOSConfig.h; sourceTree = "<group>"; };
|
||||||
|
65904E54146128A500FD9482 /* op_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = op_config.h; sourceTree = "<group>"; };
|
||||||
|
65904E55146128A500FD9482 /* openpilot.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = openpilot.h; sourceTree = "<group>"; };
|
||||||
|
65904E56146128A500FD9482 /* pios_config.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_config.h; sourceTree = "<group>"; };
|
||||||
|
65904E57146128A500FD9482 /* taskmonitor.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = taskmonitor.h; sourceTree = "<group>"; };
|
||||||
|
65904E58146128A500FD9482 /* pios_board.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_board.c; sourceTree = "<group>"; };
|
||||||
|
65904E59146128A500FD9482 /* revolution.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = revolution.c; sourceTree = "<group>"; };
|
||||||
|
65904E5A146128A500FD9482 /* taskmonitor.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = taskmonitor.c; sourceTree = "<group>"; };
|
||||||
|
65904E5B146128A500FD9482 /* test.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = test.c; sourceTree = "<group>"; };
|
||||||
|
65904E5C146128A500FD9482 /* UAVObjects.inc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.pascal; path = UAVObjects.inc; sourceTree = "<group>"; };
|
||||||
659ED317122226B60011010E /* ahrssettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = ahrssettings.xml; sourceTree = "<group>"; };
|
659ED317122226B60011010E /* ahrssettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = ahrssettings.xml; sourceTree = "<group>"; };
|
||||||
65B35D7F121C261E003EAD18 /* bin.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = bin.pro; sourceTree = "<group>"; };
|
65B35D7F121C261E003EAD18 /* bin.pro */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; path = bin.pro; sourceTree = "<group>"; };
|
||||||
65B35D80121C261E003EAD18 /* openpilotgcs */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.sh; path = openpilotgcs; sourceTree = "<group>"; };
|
65B35D80121C261E003EAD18 /* openpilotgcs */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.script.sh; path = openpilotgcs; sourceTree = "<group>"; };
|
||||||
@ -2866,7 +2877,6 @@
|
|||||||
65D1FBD413F504C9006374A6 /* pios_hmc5883.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_hmc5883.h; sourceTree = "<group>"; };
|
65D1FBD413F504C9006374A6 /* pios_hmc5883.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_hmc5883.h; sourceTree = "<group>"; };
|
||||||
65D1FBD613F50CD5006374A6 /* pios_hmc5883.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_hmc5883.c; sourceTree = "<group>"; };
|
65D1FBD613F50CD5006374A6 /* pios_hmc5883.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_hmc5883.c; sourceTree = "<group>"; };
|
||||||
65D1FBD713F5146F006374A6 /* pios_bmp085.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_bmp085.c; sourceTree = "<group>"; };
|
65D1FBD713F5146F006374A6 /* pios_bmp085.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_bmp085.c; sourceTree = "<group>"; };
|
||||||
65D1FBD813F51865006374A6 /* pios_bmp085.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_bmp085.c; sourceTree = "<group>"; };
|
|
||||||
65D1FBD913F51AB7006374A6 /* pios_imu3000.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_imu3000.c; sourceTree = "<group>"; };
|
65D1FBD913F51AB7006374A6 /* pios_imu3000.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_imu3000.c; sourceTree = "<group>"; };
|
||||||
65D1FBDA13F51AE1006374A6 /* pios_imu3000.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_imu3000.h; sourceTree = "<group>"; };
|
65D1FBDA13F51AE1006374A6 /* pios_imu3000.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_imu3000.h; sourceTree = "<group>"; };
|
||||||
65D1FBE713F53477006374A6 /* pios_bl_helper.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_bl_helper.h; sourceTree = "<group>"; };
|
65D1FBE713F53477006374A6 /* pios_bl_helper.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_bl_helper.h; sourceTree = "<group>"; };
|
||||||
@ -4082,6 +4092,7 @@
|
|||||||
657CEEB5121DBC49007A1FBE /* flight */ = {
|
657CEEB5121DBC49007A1FBE /* flight */ = {
|
||||||
isa = PBXGroup;
|
isa = PBXGroup;
|
||||||
children = (
|
children = (
|
||||||
|
65904E3F146128A500FD9482 /* Revolution */,
|
||||||
6560A3B013EE2FCB00105DA5 /* INS */,
|
6560A3B013EE2FCB00105DA5 /* INS */,
|
||||||
65FF4BB313791C3300146BE4 /* Bootloaders */,
|
65FF4BB313791C3300146BE4 /* Bootloaders */,
|
||||||
65F93B9012EE09280047DB36 /* PipXtreme */,
|
65F93B9012EE09280047DB36 /* PipXtreme */,
|
||||||
@ -4103,7 +4114,6 @@
|
|||||||
657CEEB6121DBC63007A1FBE /* Libraries */ = {
|
657CEEB6121DBC63007A1FBE /* Libraries */ = {
|
||||||
isa = PBXGroup;
|
isa = PBXGroup;
|
||||||
children = (
|
children = (
|
||||||
65643CEC141429A100A32F59 /* NMEA.c */,
|
|
||||||
6549E0D21279B3C800C5476F /* fifo_buffer.c */,
|
6549E0D21279B3C800C5476F /* fifo_buffer.c */,
|
||||||
651913371256C5240039C0A3 /* ahrs_comm_objects.c */,
|
651913371256C5240039C0A3 /* ahrs_comm_objects.c */,
|
||||||
651913381256C5240039C0A3 /* ahrs_spi_comm.c */,
|
651913381256C5240039C0A3 /* ahrs_spi_comm.c */,
|
||||||
@ -4118,7 +4128,6 @@
|
|||||||
657CEEB8121DBC63007A1FBE /* inc */ = {
|
657CEEB8121DBC63007A1FBE /* inc */ = {
|
||||||
isa = PBXGroup;
|
isa = PBXGroup;
|
||||||
children = (
|
children = (
|
||||||
65643CEE141429AF00A32F59 /* NMEA.h */,
|
|
||||||
6549E0D31279B3CF00C5476F /* fifo_buffer.h */,
|
6549E0D31279B3CF00C5476F /* fifo_buffer.h */,
|
||||||
6519133A1256C52B0039C0A3 /* ahrs_comm_objects.h */,
|
6519133A1256C52B0039C0A3 /* ahrs_comm_objects.h */,
|
||||||
6519133B1256C52B0039C0A3 /* ahrs_spi_comm.h */,
|
6519133B1256C52B0039C0A3 /* ahrs_spi_comm.h */,
|
||||||
@ -4129,6 +4138,64 @@
|
|||||||
path = inc;
|
path = inc;
|
||||||
sourceTree = "<group>";
|
sourceTree = "<group>";
|
||||||
};
|
};
|
||||||
|
65904E3F146128A500FD9482 /* Revolution */ = {
|
||||||
|
isa = PBXGroup;
|
||||||
|
children = (
|
||||||
|
65904E40146128A500FD9482 /* .Makefile.swp */,
|
||||||
|
65904E41146128A500FD9482 /* inc */,
|
||||||
|
65904E47146128A500FD9482 /* ins.c */,
|
||||||
|
65904E48146128A500FD9482 /* insgps13state.c */,
|
||||||
|
65904E49146128A500FD9482 /* insgps16state.c */,
|
||||||
|
65904E4A146128A500FD9482 /* insgps_helper.c */,
|
||||||
|
65904E4B146128A500FD9482 /* Makefile */,
|
||||||
|
65904E4C146128A500FD9482 /* System */,
|
||||||
|
65904E5B146128A500FD9482 /* test.c */,
|
||||||
|
65904E5C146128A500FD9482 /* UAVObjects.inc */,
|
||||||
|
);
|
||||||
|
name = Revolution;
|
||||||
|
path = ../../Revolution;
|
||||||
|
sourceTree = "<group>";
|
||||||
|
};
|
||||||
|
65904E41146128A500FD9482 /* inc */ = {
|
||||||
|
isa = PBXGroup;
|
||||||
|
children = (
|
||||||
|
65904E42146128A500FD9482 /* ahrs_timer.h */,
|
||||||
|
65904E43146128A500FD9482 /* ins.h */,
|
||||||
|
65904E44146128A500FD9482 /* ins_fsm.h */,
|
||||||
|
65904E45146128A500FD9482 /* insgps.h */,
|
||||||
|
65904E46146128A500FD9482 /* insgps_helper.h */,
|
||||||
|
);
|
||||||
|
path = inc;
|
||||||
|
sourceTree = "<group>";
|
||||||
|
};
|
||||||
|
65904E4C146128A500FD9482 /* System */ = {
|
||||||
|
isa = PBXGroup;
|
||||||
|
children = (
|
||||||
|
65904E4D146128A500FD9482 /* alarms.c */,
|
||||||
|
65904E4E146128A500FD9482 /* cm3_fault_handlers.c */,
|
||||||
|
65904E4F146128A500FD9482 /* dcc_stdio.c */,
|
||||||
|
65904E50146128A500FD9482 /* inc */,
|
||||||
|
65904E58146128A500FD9482 /* pios_board.c */,
|
||||||
|
65904E59146128A500FD9482 /* revolution.c */,
|
||||||
|
65904E5A146128A500FD9482 /* taskmonitor.c */,
|
||||||
|
);
|
||||||
|
path = System;
|
||||||
|
sourceTree = "<group>";
|
||||||
|
};
|
||||||
|
65904E50146128A500FD9482 /* inc */ = {
|
||||||
|
isa = PBXGroup;
|
||||||
|
children = (
|
||||||
|
65904E51146128A500FD9482 /* alarms.h */,
|
||||||
|
65904E52146128A500FD9482 /* dcc_stdio.h */,
|
||||||
|
65904E53146128A500FD9482 /* FreeRTOSConfig.h */,
|
||||||
|
65904E54146128A500FD9482 /* op_config.h */,
|
||||||
|
65904E55146128A500FD9482 /* openpilot.h */,
|
||||||
|
65904E56146128A500FD9482 /* pios_config.h */,
|
||||||
|
65904E57146128A500FD9482 /* taskmonitor.h */,
|
||||||
|
);
|
||||||
|
path = inc;
|
||||||
|
sourceTree = "<group>";
|
||||||
|
};
|
||||||
65B35D7D121C261E003EAD18 /* ground */ = {
|
65B35D7D121C261E003EAD18 /* ground */ = {
|
||||||
isa = PBXGroup;
|
isa = PBXGroup;
|
||||||
children = (
|
children = (
|
||||||
@ -7959,8 +8026,6 @@
|
|||||||
65C35E5812EFB2F3004811C2 /* attituderaw.xml */,
|
65C35E5812EFB2F3004811C2 /* attituderaw.xml */,
|
||||||
65E410AE12F65AEA00725888 /* attitudesettings.xml */,
|
65E410AE12F65AEA00725888 /* attitudesettings.xml */,
|
||||||
65C35E5912EFB2F3004811C2 /* baroaltitude.xml */,
|
65C35E5912EFB2F3004811C2 /* baroaltitude.xml */,
|
||||||
65C35E5A12EFB2F3004811C2 /* batterysettings.xml */,
|
|
||||||
655B1A8E13B2FC0900B0E48D /* camerastabsettings.xml */,
|
|
||||||
652C8568132B632A00BFCC70 /* firmwareiapobj.xml */,
|
652C8568132B632A00BFCC70 /* firmwareiapobj.xml */,
|
||||||
65C35E5C12EFB2F3004811C2 /* flightbatterystate.xml */,
|
65C35E5C12EFB2F3004811C2 /* flightbatterystate.xml */,
|
||||||
65C35E5D12EFB2F3004811C2 /* flightplancontrol.xml */,
|
65C35E5D12EFB2F3004811C2 /* flightplancontrol.xml */,
|
||||||
@ -7974,7 +8039,6 @@
|
|||||||
65C35E6412EFB2F3004811C2 /* gpstime.xml */,
|
65C35E6412EFB2F3004811C2 /* gpstime.xml */,
|
||||||
65C35E6512EFB2F3004811C2 /* guidancesettings.xml */,
|
65C35E6512EFB2F3004811C2 /* guidancesettings.xml */,
|
||||||
65C35E6612EFB2F3004811C2 /* homelocation.xml */,
|
65C35E6612EFB2F3004811C2 /* homelocation.xml */,
|
||||||
65E6D80713E3A4D0002A557A /* hwsettings.xml */,
|
|
||||||
65C35E6712EFB2F3004811C2 /* i2cstats.xml */,
|
65C35E6712EFB2F3004811C2 /* i2cstats.xml */,
|
||||||
65C35E6812EFB2F3004811C2 /* manualcontrolcommand.xml */,
|
65C35E6812EFB2F3004811C2 /* manualcontrolcommand.xml */,
|
||||||
65C35E6912EFB2F3004811C2 /* manualcontrolsettings.xml */,
|
65C35E6912EFB2F3004811C2 /* manualcontrolsettings.xml */,
|
||||||
|
@ -49,7 +49,7 @@ endif
|
|||||||
FLASH_TOOL = OPENOCD
|
FLASH_TOOL = OPENOCD
|
||||||
|
|
||||||
# List of modules to include
|
# List of modules to include
|
||||||
MODULES = Actuator Telemetry ManualControl Stabilization FirmwareIAP
|
MODULES = Actuator Telemetry ManualControl Stabilization
|
||||||
PYMODULES = FlightPlan
|
PYMODULES = FlightPlan
|
||||||
|
|
||||||
# Paths
|
# Paths
|
||||||
@ -120,7 +120,11 @@ SRC += $(OPSYSTEM)/taskmonitor.c
|
|||||||
SRC += $(OPUAVTALK)/uavtalk.c
|
SRC += $(OPUAVTALK)/uavtalk.c
|
||||||
SRC += $(OPUAVOBJ)/uavobjectmanager.c
|
SRC += $(OPUAVOBJ)/uavobjectmanager.c
|
||||||
SRC += $(OPUAVOBJ)/eventdispatcher.c
|
SRC += $(OPUAVOBJ)/eventdispatcher.c
|
||||||
|
|
||||||
|
#ifeq ($(DEBUG),YES)
|
||||||
|
SRC += $(OPSYSTEM)/dcc_stdio.c
|
||||||
SRC += $(OPSYSTEM)/cm3_fault_handlers.c
|
SRC += $(OPSYSTEM)/cm3_fault_handlers.c
|
||||||
|
#endif
|
||||||
|
|
||||||
SRC += $(FLIGHTLIB)/CoordinateConversions.c
|
SRC += $(FLIGHTLIB)/CoordinateConversions.c
|
||||||
SRC += $(FLIGHTLIB)/fifo_buffer.c
|
SRC += $(FLIGHTLIB)/fifo_buffer.c
|
||||||
@ -130,7 +134,9 @@ SRC += $(FLIGHTLIB)/NMEA.c
|
|||||||
include $(PIOS)/STM32F4xx/library.mk
|
include $(PIOS)/STM32F4xx/library.mk
|
||||||
|
|
||||||
## PIOS Hardware (Common)
|
## PIOS Hardware (Common)
|
||||||
|
SRC += $(PIOSCOMMON)/pios_crc.c
|
||||||
SRC += $(PIOSCOMMON)/pios_com.c
|
SRC += $(PIOSCOMMON)/pios_com.c
|
||||||
|
SRC += $(PIOSCOMMON)/pios_rcvr.c
|
||||||
SRC += $(PIOSCOMMON)/printf-stdarg.c
|
SRC += $(PIOSCOMMON)/printf-stdarg.c
|
||||||
|
|
||||||
#SRC += $(PIOSCOMMON)/pios_bl_helper.c
|
#SRC += $(PIOSCOMMON)/pios_bl_helper.c
|
||||||
|
@ -51,7 +51,7 @@
|
|||||||
#define PIOS_INCLUDE_SPI
|
#define PIOS_INCLUDE_SPI
|
||||||
#define PIOS_INCLUDE_SYS
|
#define PIOS_INCLUDE_SYS
|
||||||
#define PIOS_INCLUDE_USART
|
#define PIOS_INCLUDE_USART
|
||||||
#define PIOS_INCLUDE_USB_HID
|
//#define PIOS_INCLUDE_USB_HID
|
||||||
|
|
||||||
#define PIOS_INCLUDE_GPS
|
#define PIOS_INCLUDE_GPS
|
||||||
#define PIOS_INCLUDE_BMA180
|
#define PIOS_INCLUDE_BMA180
|
||||||
|
@ -33,7 +33,11 @@
|
|||||||
|
|
||||||
#if defined(PIOS_INCLUDE_SPI)
|
#if defined(PIOS_INCLUDE_SPI)
|
||||||
|
|
||||||
|
#include <openpilot.h>
|
||||||
#include <pios_spi_priv.h>
|
#include <pios_spi_priv.h>
|
||||||
|
#include <uavobjectsinit.h>
|
||||||
|
#include <hwsettings.h>
|
||||||
|
#include "manualcontrolsettings.h"
|
||||||
|
|
||||||
/* SPI2 Interface
|
/* SPI2 Interface
|
||||||
* - Used for mainboard communications
|
* - Used for mainboard communications
|
||||||
@ -548,11 +552,22 @@ void PIOS_I2C_gyro_adapter_er_irq_handler(void)
|
|||||||
|
|
||||||
#endif /* PIOS_INCLUDE_I2C */
|
#endif /* PIOS_INCLUDE_I2C */
|
||||||
|
|
||||||
|
#if defined(PIOS_INCLUDE_RCVR)
|
||||||
|
#include "pios_rcvr_priv.h"
|
||||||
|
|
||||||
|
/* 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];
|
||||||
|
#endif
|
||||||
|
|
||||||
extern const struct pios_com_driver pios_usart_com_driver;
|
extern const struct pios_com_driver pios_usart_com_driver;
|
||||||
|
|
||||||
uint32_t pios_com_aux_id;
|
uint32_t pios_com_aux_id;
|
||||||
uint32_t pios_com_gps_id;
|
uint32_t pios_com_gps_id;
|
||||||
|
uint32_t pios_com_telem_usb_id;
|
||||||
|
uint32_t pios_com_telem_rf_id;
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@ -776,15 +791,6 @@ void PIOS_Board_Init(void) {
|
|||||||
PIOS_HMC5883_Init(&pios_hmc5883_cfg);
|
PIOS_HMC5883_Init(&pios_hmc5883_cfg);
|
||||||
PIOS_BMP085_Init(&pios_bmp085_cfg);
|
PIOS_BMP085_Init(&pios_bmp085_cfg);
|
||||||
|
|
||||||
|
|
||||||
/* Set up the SPI interface to the OP board */
|
|
||||||
#include "ahrs_spi_comm.h"
|
|
||||||
AhrsInitComms();
|
|
||||||
if (PIOS_SPI_Init(&pios_spi_op_id, &pios_spi_op_cfg)) {
|
|
||||||
PIOS_DEBUG_Assert(0);
|
|
||||||
}
|
|
||||||
|
|
||||||
AhrsConnect(pios_spi_op_id);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -1,69 +0,0 @@
|
|||||||
/**
|
|
||||||
******************************************************************************
|
|
||||||
* @addtogroup INS INS
|
|
||||||
|
|
||||||
* @brief The INS configuration
|
|
||||||
*
|
|
||||||
* @{
|
|
||||||
* @addtogroup INS_Main
|
|
||||||
* @brief INS configuration
|
|
||||||
* @{
|
|
||||||
*
|
|
||||||
* @file pios_config.h
|
|
||||||
* @author David "Buzz" Carlson (buzz@chebuzz.com)
|
|
||||||
* The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
|
|
||||||
* @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
|
|
||||||
|
|
||||||
/* Enable/Disable PiOS Modules */
|
|
||||||
#define PIOS_INCLUDE_DELAY
|
|
||||||
#define PIOS_INCLUDE_I2C
|
|
||||||
#define PIOS_INCLUDE_IRQ
|
|
||||||
#define PIOS_INCLUDE_LED
|
|
||||||
#define PIOS_INCLUDE_SPI
|
|
||||||
#define PIOS_INCLUDE_SYS
|
|
||||||
#define PIOS_INCLUDE_USART
|
|
||||||
#define PIOS_INCLUDE_COM
|
|
||||||
#define PIOS_INCLUDE_COM_AUX
|
|
||||||
#define PIOS_INCLUDE_GPS
|
|
||||||
#define PIOS_INCLUDE_BMA180
|
|
||||||
#define PIOS_INCLUDE_HMC5883
|
|
||||||
#define PIOS_INCLUDE_BMP085
|
|
||||||
#define PIOS_INCLUDE_IMU3000
|
|
||||||
//#define PIOS_INCLUDE_GPIO
|
|
||||||
|
|
||||||
#define PIOS_INCLUDE_BMA180
|
|
||||||
#define PIOS_INCLUDE_FREERTOS
|
|
||||||
|
|
||||||
/* COM Module */
|
|
||||||
#define GPS_BAUDRATE 19200
|
|
||||||
#define AUXUART_ENABLED 0
|
|
||||||
#define AUXUART_BAUDRATE 19200
|
|
||||||
|
|
||||||
#endif /* PIOS_CONFIG_H */
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @}
|
|
||||||
* @}
|
|
||||||
*/
|
|
Loading…
Reference in New Issue
Block a user