diff --git a/flight/CopterControl/Makefile b/flight/CopterControl/Makefile index 89d36996c..687ecafc6 100644 --- a/flight/CopterControl/Makefile +++ b/flight/CopterControl/Makefile @@ -167,7 +167,8 @@ SRC += $(OPUAVSYNTHDIR)/attitudesettings.c SRC += $(OPUAVSYNTHDIR)/camerastabsettings.c SRC += $(OPUAVSYNTHDIR)/cameradesired.c SRC += $(OPUAVSYNTHDIR)/hwsettings.c - +SRC += $(OPUAVSYNTHDIR)/gcsreceiver.c +SRC += $(OPUAVSYNTHDIR)/receiveractivity.c SRC += $(OPUAVSYNTHDIR)/taskinfo.c SRC += $(OPUAVSYNTHDIR)/mixerstatus.c SRC += $(OPUAVSYNTHDIR)/ratedesired.c @@ -194,6 +195,7 @@ SRC += $(PIOSSTM32F10X)/pios_exti.c SRC += $(PIOSSTM32F10X)/pios_rtc.c SRC += $(PIOSSTM32F10X)/pios_wdg.c SRC += $(PIOSSTM32F10X)/pios_iap.c +SRC += $(PIOSSTM32F10X)/pios_tim.c # PIOS USB related files (seperated to make code maintenance more easy) @@ -211,6 +213,7 @@ SRC += $(PIOSCOMMON)/pios_com.c SRC += $(PIOSCOMMON)/pios_i2c_esc.c SRC += $(PIOSCOMMON)/pios_bl_helper.c SRC += $(PIOSCOMMON)/pios_rcvr.c +SRC += $(PIOSCOMMON)/pios_gcsrcvr.c SRC += $(PIOSCOMMON)/printf-stdarg.c ## Libraries for flight calculations SRC += $(FLIGHTLIB)/fifo_buffer.c diff --git a/flight/CopterControl/System/inc/FreeRTOSConfig.h b/flight/CopterControl/System/inc/FreeRTOSConfig.h index 8da6a8667..994956008 100644 --- a/flight/CopterControl/System/inc/FreeRTOSConfig.h +++ b/flight/CopterControl/System/inc/FreeRTOSConfig.h @@ -26,6 +26,7 @@ #define configUSE_PREEMPTION 1 #define configUSE_IDLE_HOOK 1 #define configUSE_TICK_HOOK 0 +#define configUSE_MALLOC_FAILED_HOOK 1 #define configCPU_CLOCK_HZ ( ( unsigned long ) 72000000 ) #define configTICK_RATE_HZ ( ( portTickType ) 1000 ) #define configMAX_PRIORITIES ( ( unsigned portBASE_TYPE ) 5 ) diff --git a/flight/CopterControl/System/inc/pios_config.h b/flight/CopterControl/System/inc/pios_config.h index 8e09d71ca..bab05551d 100644 --- a/flight/CopterControl/System/inc/pios_config.h +++ b/flight/CopterControl/System/inc/pios_config.h @@ -48,8 +48,9 @@ /* Supported receiver interfaces */ #define PIOS_INCLUDE_SPEKTRUM #define PIOS_INCLUDE_SBUS -//#define PIOS_INCLUDE_PPM +#define PIOS_INCLUDE_PPM #define PIOS_INCLUDE_PWM +#define PIOS_INCLUDE_GCSRCVR /* Supported USART-based PIOS modules */ #define PIOS_INCLUDE_TELEMETRY_RF diff --git a/flight/CopterControl/System/pios_board.c b/flight/CopterControl/System/pios_board.c index d512ae989..d9023ffb9 100644 --- a/flight/CopterControl/System/pios_board.c +++ b/flight/CopterControl/System/pios_board.c @@ -32,6 +32,7 @@ #include #include #include +#include #if defined(PIOS_INCLUDE_SPI) @@ -195,6 +196,220 @@ void PIOS_ADC_handler() { PIOS_ADC_DMA_Handler(); } +#include "pios_tim_priv.h" + +static const TIM_TimeBaseInitTypeDef tim_1_2_3_4_time_base = { + .TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1, + .TIM_ClockDivision = TIM_CKD_DIV1, + .TIM_CounterMode = TIM_CounterMode_Up, + .TIM_Period = ((1000000 / PIOS_SERVO_UPDATE_HZ) - 1), + .TIM_RepetitionCounter = 0x0000, +}; + +static const struct pios_tim_clock_cfg tim_1_cfg = { + .timer = TIM1, + .time_base_init = &tim_1_2_3_4_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM1_CC_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_clock_cfg tim_2_cfg = { + .timer = TIM2, + .time_base_init = &tim_1_2_3_4_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM2_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_clock_cfg tim_3_cfg = { + .timer = TIM3, + .time_base_init = &tim_1_2_3_4_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM3_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_clock_cfg tim_4_cfg = { + .timer = TIM4, + .time_base_init = &tim_1_2_3_4_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM4_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_channel pios_tim_rcvrport_all_channels[] = { + { + .timer = TIM4, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_6, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM3, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_5, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + .remap = GPIO_PartialRemap_TIM3, + }, + { + .timer = TIM3, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_0, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM3, + .timer_chan = TIM_Channel_4, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_1, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM2, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_0, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM2, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_1, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, +}; + +static const struct pios_tim_channel pios_tim_servoport_all_pins[] = { + { + .timer = TIM4, + .timer_chan = TIM_Channel_4, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_9, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM4, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_8, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM4, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_7, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM1, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_8, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM3, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_4, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + .remap = GPIO_PartialRemap_TIM3, + }, + { + .timer = TIM2, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_2, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, +}; + #if defined(PIOS_INCLUDE_USART) #include "pios_usart_priv.h" @@ -564,121 +779,40 @@ void PIOS_RTC_IRQ_Handler (void) * Servo outputs */ #include -static const struct pios_servo_channel pios_servo_channels[] = { - { - .timer = TIM4, - .port = GPIOB, - .channel = TIM_Channel_4, - .pin = GPIO_Pin_9, - }, - { - .timer = TIM4, - .port = GPIOB, - .channel = TIM_Channel_3, - .pin = GPIO_Pin_8, - }, - { - .timer = TIM4, - .port = GPIOB, - .channel = TIM_Channel_2, - .pin = GPIO_Pin_7, - }, - { - .timer = TIM1, - .port = GPIOA, - .channel = TIM_Channel_1, - .pin = GPIO_Pin_8, - }, - { /* needs to remap to alternative function */ - .timer = TIM3, - .port = GPIOB, - .channel = TIM_Channel_1, - .pin = GPIO_Pin_4, - }, - { - .timer = TIM2, - .port = GPIOA, - .channel = TIM_Channel_3, - .pin = GPIO_Pin_2, - }, -}; const struct pios_servo_cfg pios_servo_cfg = { - .tim_base_init = { - .TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1, - .TIM_ClockDivision = TIM_CKD_DIV1, - .TIM_CounterMode = TIM_CounterMode_Up, - .TIM_Period = ((1000000 / PIOS_SERVO_UPDATE_HZ) - 1), - .TIM_RepetitionCounter = 0x0000, - }, .tim_oc_init = { .TIM_OCMode = TIM_OCMode_PWM1, .TIM_OutputState = TIM_OutputState_Enable, .TIM_OutputNState = TIM_OutputNState_Disable, - .TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION, + .TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION, .TIM_OCPolarity = TIM_OCPolarity_High, .TIM_OCNPolarity = TIM_OCPolarity_High, .TIM_OCIdleState = TIM_OCIdleState_Reset, .TIM_OCNIdleState = TIM_OCNIdleState_Reset, }, - .gpio_init = { - .GPIO_Mode = GPIO_Mode_AF_PP, - .GPIO_Speed = GPIO_Speed_2MHz, - }, - .remap = GPIO_PartialRemap_TIM3, - .channels = pios_servo_channels, - .num_channels = NELEMENTS(pios_servo_channels), + .channels = pios_tim_servoport_all_pins, + .num_channels = NELEMENTS(pios_tim_servoport_all_pins), }; -#if defined(PIOS_INCLUDE_PWM) && defined(PIOS_INCLUDE_PPM) -#error Cannot define both PIOS_INCLUDE_PWM and PIOS_INCLUDE_PPM at the same time (yet) -#endif - /* * PPM Inputs */ #if defined(PIOS_INCLUDE_PPM) #include -void TIM4_IRQHandler(); -void TIM4_IRQHandler() __attribute__ ((alias ("PIOS_TIM4_irq_handler"))); const struct pios_ppm_cfg pios_ppm_cfg = { - .tim_base_init = { - .TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1, /* For 1 uS accuracy */ - .TIM_ClockDivision = TIM_CKD_DIV1, - .TIM_CounterMode = TIM_CounterMode_Up, - .TIM_Period = 0xFFFF, /* shared timer, make sure init correctly in outputs */ - .TIM_RepetitionCounter = 0x0000, - }, .tim_ic_init = { - .TIM_Channel = TIM_Channel_1, .TIM_ICPolarity = TIM_ICPolarity_Rising, .TIM_ICSelection = TIM_ICSelection_DirectTI, .TIM_ICPrescaler = TIM_ICPSC_DIV1, .TIM_ICFilter = 0x0, }, - .gpio_init = { - .GPIO_Pin = GPIO_Pin_6, - .GPIO_Mode = GPIO_Mode_IPD, - .GPIO_Speed = GPIO_Speed_2MHz, - }, - .remap = 0, - .irq = { - .init = { - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .timer = TIM4, - .port = GPIOB, - .ccr = TIM_IT_CC1, + /* Use only the first channel for ppm */ + .channels = &pios_tim_rcvrport_all_channels[0], + .num_channels = 1, }; -void PIOS_TIM4_irq_handler() -{ - PIOS_PPM_irq_handler(); -} #endif /* PIOS_INCLUDE_PPM */ /* @@ -687,98 +821,16 @@ void PIOS_TIM4_irq_handler() #if defined(PIOS_INCLUDE_PWM) #include -static const struct pios_pwm_channel pios_pwm_channels[] = { - { - .timer = TIM4, - .port = GPIOB, - .ccr = TIM_IT_CC1, - .channel = TIM_Channel_1, - .pin = GPIO_Pin_6, - }, - { - .timer = TIM3, - .port = GPIOB, - .ccr = TIM_IT_CC2, - .channel = TIM_Channel_2, - .pin = GPIO_Pin_5, - }, - { - .timer = TIM3, - .port = GPIOB, - .ccr = TIM_IT_CC3, - .channel = TIM_Channel_3, - .pin = GPIO_Pin_0 - }, - { - .timer = TIM3, - .port = GPIOB, - .ccr = TIM_IT_CC4, - .channel = TIM_Channel_4, - .pin = GPIO_Pin_1, - }, - { - .timer = TIM2, - .port = GPIOA, - .ccr = TIM_IT_CC1, - .channel = TIM_Channel_1, - .pin = GPIO_Pin_0, - }, - { - .timer = TIM2, - .port = GPIOA, - .ccr = TIM_IT_CC2, - .channel = TIM_Channel_2, - .pin = GPIO_Pin_1, - }, -}; - -void TIM2_IRQHandler(); -void TIM3_IRQHandler(); -void TIM4_IRQHandler(); -void TIM2_IRQHandler() __attribute__ ((alias ("PIOS_TIM2_irq_handler"))); -void TIM3_IRQHandler() __attribute__ ((alias ("PIOS_TIM3_irq_handler"))); -void TIM4_IRQHandler() __attribute__ ((alias ("PIOS_TIM4_irq_handler"))); const struct pios_pwm_cfg pios_pwm_cfg = { - .tim_base_init = { - .TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1, - .TIM_ClockDivision = TIM_CKD_DIV1, - .TIM_CounterMode = TIM_CounterMode_Up, - .TIM_Period = 0xFFFF, - .TIM_RepetitionCounter = 0x0000, - }, .tim_ic_init = { .TIM_ICPolarity = TIM_ICPolarity_Rising, .TIM_ICSelection = TIM_ICSelection_DirectTI, .TIM_ICPrescaler = TIM_ICPSC_DIV1, - .TIM_ICFilter = 0x0, + .TIM_ICFilter = 0x0, }, - .gpio_init = { - .GPIO_Mode = GPIO_Mode_IPD, - .GPIO_Speed = GPIO_Speed_2MHz, - }, - .remap = 0, - .irq = { - .init = { - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .channels = pios_pwm_channels, - .num_channels = NELEMENTS(pios_pwm_channels), + .channels = pios_tim_rcvrport_all_channels, + .num_channels = NELEMENTS(pios_tim_rcvrport_all_channels), }; -void PIOS_TIM2_irq_handler() -{ - PIOS_PWM_irq_handler(TIM2); -} -void PIOS_TIM3_irq_handler() -{ - PIOS_PWM_irq_handler(TIM3); -} -void PIOS_TIM4_irq_handler() -{ - PIOS_PWM_irq_handler(TIM4); -} #endif #if defined(PIOS_INCLUDE_I2C) @@ -856,11 +908,19 @@ void PIOS_I2C_main_adapter_er_irq_handler(void) #endif /* PIOS_INCLUDE_I2C */ +#if defined(PIOS_INCLUDE_GCSRCVR) +#include "pios_gcsrcvr_priv.h" +#endif /* PIOS_INCLUDE_GCSRCVR */ + #if defined(PIOS_INCLUDE_RCVR) #include "pios_rcvr_priv.h" -struct pios_rcvr_channel_map pios_rcvr_channel_to_id_map[PIOS_RCVR_MAX_CHANNELS]; -uint32_t pios_rcvr_max_channel; +/* 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 /* PIOS_INCLUDE_RCVR */ #if defined(PIOS_INCLUDE_USB_HID) @@ -922,7 +982,15 @@ void PIOS_Board_Init(void) { /* Initialize the task monitor library */ TaskMonitorInitialize(); + /* Set up pulse timers */ + PIOS_TIM_InitClock(&tim_1_cfg); + PIOS_TIM_InitClock(&tim_2_cfg); + PIOS_TIM_InitClock(&tim_3_cfg); + PIOS_TIM_InitClock(&tim_4_cfg); + /* Configure the main IO port */ + uint8_t hwsettings_DSMxBind; + HwSettingsDSMxBindGet(&hwsettings_DSMxBind); uint8_t hwsettings_cc_mainport; HwSettingsCC_MainPortGet(&hwsettings_cc_mainport); @@ -982,7 +1050,8 @@ void PIOS_Board_Init(void) { } #endif /* PIOS_INCLUDE_GPS */ break; - case HWSETTINGS_CC_MAINPORT_SPEKTRUM: + case HWSETTINGS_CC_MAINPORT_SPEKTRUM1: + case HWSETTINGS_CC_MAINPORT_SPEKTRUM2: #if defined(PIOS_INCLUDE_SPEKTRUM) { uint32_t pios_usart_spektrum_id; @@ -991,9 +1060,19 @@ void PIOS_Board_Init(void) { } uint32_t pios_spektrum_id; - if (PIOS_SPEKTRUM_Init(&pios_spektrum_id, &pios_spektrum_main_cfg, &pios_usart_com_driver, pios_usart_spektrum_id, false)) { + if (PIOS_SPEKTRUM_Init(&pios_spektrum_id, &pios_spektrum_main_cfg, &pios_usart_com_driver, pios_usart_spektrum_id, 0)) { PIOS_Assert(0); } + + uint32_t pios_spektrum_rcvr_id; + if (PIOS_RCVR_Init(&pios_spektrum_rcvr_id, &pios_spektrum_rcvr_driver, pios_spektrum_id)) { + PIOS_Assert(0); + } + if (hwsettings_cc_mainport == HWSETTINGS_CC_MAINPORT_SPEKTRUM1) { + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SPEKTRUM1] = pios_spektrum_rcvr_id; + } else { + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SPEKTRUM2] = pios_spektrum_rcvr_id; + } } #endif /* PIOS_INCLUDE_SPEKTRUM */ break; @@ -1044,7 +1123,8 @@ void PIOS_Board_Init(void) { } #endif /* PIOS_INCLUDE_GPS */ break; - case HWSETTINGS_CC_FLEXIPORT_SPEKTRUM: + case HWSETTINGS_CC_FLEXIPORT_SPEKTRUM1: + case HWSETTINGS_CC_FLEXIPORT_SPEKTRUM2: #if defined(PIOS_INCLUDE_SPEKTRUM) { uint32_t pios_usart_spektrum_id; @@ -1053,9 +1133,19 @@ void PIOS_Board_Init(void) { } uint32_t pios_spektrum_id; - if (PIOS_SPEKTRUM_Init(&pios_spektrum_id, &pios_spektrum_flexi_cfg, &pios_usart_com_driver, pios_usart_spektrum_id, false)) { + if (PIOS_SPEKTRUM_Init(&pios_spektrum_id, &pios_spektrum_flexi_cfg, &pios_usart_com_driver, pios_usart_spektrum_id, hwsettings_DSMxBind)) { PIOS_Assert(0); } + + uint32_t pios_spektrum_rcvr_id; + if (PIOS_RCVR_Init(&pios_spektrum_rcvr_id, &pios_spektrum_rcvr_driver, pios_spektrum_id)) { + PIOS_Assert(0); + } + if (hwsettings_cc_flexiport == HWSETTINGS_CC_FLEXIPORT_SPEKTRUM1) { + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SPEKTRUM1] = pios_spektrum_rcvr_id; + } else { + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SPEKTRUM2] = pios_spektrum_rcvr_id; + } } #endif /* PIOS_INCLUDE_SPEKTRUM */ break; @@ -1072,83 +1162,61 @@ void PIOS_Board_Init(void) { break; } - /* Configure the selected receiver */ - uint8_t manualcontrolsettings_inputmode; - ManualControlSettingsInputModeGet(&manualcontrolsettings_inputmode); + /* Configure the rcvr port */ + uint8_t hwsettings_rcvrport; + HwSettingsRcvrPortGet(&hwsettings_rcvrport); - switch (manualcontrolsettings_inputmode) { - case MANUALCONTROLSETTINGS_INPUTMODE_PWM: + switch (hwsettings_rcvrport) { + case HWSETTINGS_RCVRPORT_DISABLED: + break; + case HWSETTINGS_RCVRPORT_PWM: #if defined(PIOS_INCLUDE_PWM) - PIOS_PWM_Init(); - uint32_t pios_pwm_rcvr_id; - if (PIOS_RCVR_Init(&pios_pwm_rcvr_id, &pios_pwm_rcvr_driver, 0)) { - PIOS_Assert(0); - } - for (uint8_t i = 0; - i < PIOS_PWM_NUM_INPUTS && pios_rcvr_max_channel < NELEMENTS(pios_rcvr_channel_to_id_map); - i++) { - pios_rcvr_channel_to_id_map[pios_rcvr_max_channel].id = pios_pwm_rcvr_id; - pios_rcvr_channel_to_id_map[pios_rcvr_max_channel].channel = i; - pios_rcvr_max_channel++; + { + uint32_t pios_pwm_id; + PIOS_PWM_Init(&pios_pwm_id, &pios_pwm_cfg); + + uint32_t pios_pwm_rcvr_id; + if (PIOS_RCVR_Init(&pios_pwm_rcvr_id, &pios_pwm_rcvr_driver, pios_pwm_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PWM] = pios_pwm_rcvr_id; } #endif /* PIOS_INCLUDE_PWM */ break; - case MANUALCONTROLSETTINGS_INPUTMODE_PPM: + case HWSETTINGS_RCVRPORT_PPM: #if defined(PIOS_INCLUDE_PPM) - PIOS_PPM_Init(); - uint32_t pios_ppm_rcvr_id; - if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, 0)) { - PIOS_Assert(0); - } - for (uint8_t i = 0; - i < PIOS_PPM_NUM_INPUTS && pios_rcvr_max_channel < NELEMENTS(pios_rcvr_channel_to_id_map); - i++) { - pios_rcvr_channel_to_id_map[pios_rcvr_max_channel].id = pios_ppm_rcvr_id; - pios_rcvr_channel_to_id_map[pios_rcvr_max_channel].channel = i; - pios_rcvr_max_channel++; + { + uint32_t pios_ppm_id; + PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_cfg); + + uint32_t pios_ppm_rcvr_id; + if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM] = pios_ppm_rcvr_id; } #endif /* PIOS_INCLUDE_PPM */ break; - case MANUALCONTROLSETTINGS_INPUTMODE_SPEKTRUM: -#if defined(PIOS_INCLUDE_SPEKTRUM) - if (hwsettings_cc_mainport == HWSETTINGS_CC_MAINPORT_SPEKTRUM || - hwsettings_cc_flexiport == HWSETTINGS_CC_FLEXIPORT_SPEKTRUM) { - uint32_t pios_spektrum_rcvr_id; - if (PIOS_RCVR_Init(&pios_spektrum_rcvr_id, &pios_spektrum_rcvr_driver, 0)) { - PIOS_Assert(0); - } - for (uint8_t i = 0; - i < PIOS_SPEKTRUM_NUM_INPUTS && pios_rcvr_max_channel < NELEMENTS(pios_rcvr_channel_to_id_map); - i++) { - pios_rcvr_channel_to_id_map[pios_rcvr_max_channel].id = pios_spektrum_rcvr_id; - pios_rcvr_channel_to_id_map[pios_rcvr_max_channel].channel = i; - pios_rcvr_max_channel++; - } - } -#endif /* PIOS_INCLUDE_SPEKTRUM */ - break; - case MANUALCONTROLSETTINGS_INPUTMODE_SBUS: -#if defined(PIOS_INCLUDE_SBUS) - if (hwsettings_cc_mainport == HWSETTINGS_CC_MAINPORT_SBUS) { - uint32_t pios_sbus_rcvr_id; - if (PIOS_RCVR_Init(&pios_sbus_rcvr_id, &pios_sbus_rcvr_driver, 0)) { - PIOS_Assert(0); - } - for (uint8_t i = 0; - i < SBUS_NUMBER_OF_CHANNELS && pios_rcvr_max_channel < NELEMENTS(pios_rcvr_channel_to_id_map); - i++) { - pios_rcvr_channel_to_id_map[pios_rcvr_max_channel].id = pios_sbus_rcvr_id; - pios_rcvr_channel_to_id_map[pios_rcvr_max_channel].channel = i; - pios_rcvr_max_channel++; - } - } -#endif /* PIOS_INCLUDE_SBUS */ - break; } +#if defined(PIOS_INCLUDE_GCSRCVR) + GCSReceiverInitialize(); + PIOS_GCSRCVR_Init(); + uint32_t pios_gcsrcvr_rcvr_id; + if (PIOS_RCVR_Init(&pios_gcsrcvr_rcvr_id, &pios_gcsrcvr_rcvr_driver, 0)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_GCS] = pios_gcsrcvr_rcvr_id; +#endif /* PIOS_INCLUDE_GCSRCVR */ + /* Remap AFIO pin */ GPIO_PinRemapConfig( GPIO_Remap_SWJ_NoJTRST, ENABLE); - PIOS_Servo_Init(); + +#ifndef PIOS_DEBUG_ENABLE_DEBUG_PINS + PIOS_Servo_Init(&pios_servo_cfg); +#else + PIOS_DEBUG_Init(&pios_tim_servo_all_channels, NELEMENTS(pios_tim_servo_all_channels)); +#endif /* PIOS_DEBUG_ENABLE_DEBUG_PINS */ PIOS_ADC_Init(); PIOS_GPIO_Init(); diff --git a/flight/INS/Makefile b/flight/INS/Makefile index 8b99efc9d..26c86981f 100644 --- a/flight/INS/Makefile +++ b/flight/INS/Makefile @@ -97,7 +97,7 @@ SRC += $(PIOSSTM32F2XX)/pios_delay.c SRC += $(PIOSSTM32F2XX)/pios_usart.c SRC += $(PIOSSTM32F2XX)/pios_irq.c SRC += $(PIOSSTM32F2XX)/pios_i2c.c -SRC += $(PIOSSTM32F2XX)/pios_debug.c +#SRC += $(PIOSSTM32F2XX)/pios_debug.c #SRC += $(PIOSSTM32F2XX)/pios_gpio.c SRC += $(PIOSSTM32F2XX)/pios_spi.c #SRC += $(PIOSSTM32F2XX)/pios_exti.c diff --git a/flight/INS/pios_board.c b/flight/INS/pios_board.c index 6f8f499dc..4fec2421b 100644 --- a/flight/INS/pios_board.c +++ b/flight/INS/pios_board.c @@ -723,6 +723,11 @@ void PIOS_Board_Init(void) { /* Delay system */ PIOS_DELAY_Init(); + +#ifdef PIOS_DEBUG_ENABLE_DEBUG_PINS + PIOS_DEBUG_Init(&pios_tim_servo_all_channels, NELEMENTS(pios_tim_servo_all_channels)); +#endif /* PIOS_DEBUG_ENABLE_DEBUG_PINS */ + /* IAP System Setup */ PIOS_IAP_Init(); diff --git a/flight/Libraries/ahrs_comm_objects.c b/flight/Libraries/ahrs_comm_objects.c index 1e846e18c..3bc3bff3c 100644 --- a/flight/Libraries/ahrs_comm_objects.c +++ b/flight/Libraries/ahrs_comm_objects.c @@ -24,6 +24,7 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ +#include "pios.h" #include "ahrs_spi_comm.h" #include "pios_debug.h" diff --git a/flight/Modules/GPS/GPS.c b/flight/Modules/GPS/GPS.c index 60ff80184..2e6b0901b 100644 --- a/flight/Modules/GPS/GPS.c +++ b/flight/Modules/GPS/GPS.c @@ -35,17 +35,12 @@ #include -#ifdef ENABLE_GPS_BINARY_GTOP - #include "GTOP_BIN.h" -#endif - -#if defined(ENABLE_GPS_ONESENTENCE_GTOP) || defined(ENABLE_GPS_NMEA) - #include "NMEA.h" -#endif +#include "NMEA.h" #include "gpsposition.h" #include "homelocation.h" #include "gpstime.h" +#include "gpssatellites.h" #include "WorldMagModel.h" #include "CoordinateConversions.h" @@ -62,25 +57,16 @@ static float GravityAccel(float latitude, float longitude, float altitude); // **************** // Private constants -//#define FULL_COLD_RESTART // uncomment this to tell the GPS to do a FULL COLD restart -//#define DISABLE_GPS_THRESHOLD // - #define GPS_TIMEOUT_MS 500 -#define GPS_COMMAND_RESEND_TIMEOUT_MS 2000 +#define NMEA_MAX_PACKET_LENGTH 96 // 82 max NMEA msg size plus 12 margin (because some vendors add custom crap) plus CR plus Linefeed +// same as in COM buffer + #ifdef PIOS_GPS_SETS_HOMELOCATION // Unfortunately need a good size stack for the WMM calculation - #ifdef ENABLE_GPS_BINARY_GTOP - #define STACK_SIZE_BYTES 800 - #else - #define STACK_SIZE_BYTES 800 - #endif + #define STACK_SIZE_BYTES 800 #else - #ifdef ENABLE_GPS_BINARY_GTOP - #define STACK_SIZE_BYTES 440 - #else - #define STACK_SIZE_BYTES 440 - #endif + #define STACK_SIZE_BYTES 650 #endif #define TASK_PRIORITY (tskIDLE_PRIORITY + 1) @@ -92,9 +78,7 @@ static uint32_t gpsPort; static xTaskHandle gpsTaskHandle; -#ifndef ENABLE_GPS_BINARY_GTOP - static char gps_rx_buffer[128]; -#endif +static char* gps_rx_buffer; static uint32_t timeOfLastCommandMs; static uint32_t timeOfLastUpdateMs; @@ -126,11 +110,17 @@ int32_t GPSInitialize(void) { GPSPositionInitialize(); GPSTimeInitialize(); + GPSSatellitesInitialize(); +#ifdef PIOS_GPS_SETS_HOMELOCATION HomeLocationInitialize(); +#endif // TODO: Get gps settings object gpsPort = PIOS_COM_GPS; + gps_rx_buffer = pvPortMalloc(NMEA_MAX_PACKET_LENGTH); + PIOS_Assert(gps_rx_buffer); + return 0; } MODULE_INITCALL(GPSInitialize, GPSStart) @@ -146,45 +136,11 @@ static void gpsTask(void *parameters) uint32_t timeNowMs = xTaskGetTickCount() * portTICK_RATE_MS;; GPSPositionData GpsData; -#ifdef ENABLE_GPS_BINARY_GTOP - GTOP_BIN_init(); -#else uint8_t rx_count = 0; bool start_flag = false; bool found_cr = false; int32_t gpsRxOverflow = 0; -#endif -#ifdef FULL_COLD_RESTART - // tell the GPS to do a FULL COLD restart - PIOS_COM_SendStringNonBlocking(gpsPort, "$PMTK104*37\r\n"); - timeOfLastCommandMs = timeNowMs; - while (timeNowMs - timeOfLastCommandMs < 300) // delay for 300ms to let the GPS sort itself out - { - vTaskDelay(xDelay); // Block task until next update - timeNowMs = xTaskGetTickCount() * portTICK_RATE_MS;; - } -#endif - -#ifdef DISABLE_GPS_THRESHOLD - PIOS_COM_SendStringNonBlocking(gpsPort, "$PMTK397,0*23\r\n"); -#endif - -#ifdef ENABLE_GPS_BINARY_GTOP - // switch to GTOP binary mode - PIOS_COM_SendStringNonBlocking(gpsPort ,"$PGCMD,21,1*6F\r\n"); -#endif - -#ifdef ENABLE_GPS_ONESENTENCE_GTOP - // switch to single sentence mode - PIOS_COM_SendStringNonBlocking(gpsPort, "$PGCMD,21,2*6C\r\n"); -#endif - -#ifdef ENABLE_GPS_NMEA - // switch to NMEA mode - PIOS_COM_SendStringNonBlocking(gpsPort, "$PGCMD,21,3*6D\r\n"); -#endif - numUpdates = 0; numChecksumErrors = 0; numParsingErrors = 0; @@ -195,108 +151,87 @@ static void gpsTask(void *parameters) // Loop forever while (1) { - #ifdef ENABLE_GPS_BINARY_GTOP - // GTOP BINARY GPS mode + uint8_t c; + // NMEA or SINGLE-SENTENCE GPS mode - while (PIOS_COM_ReceiveBufferUsed(gpsPort) > 0) + // This blocks the task until there is something on the buffer + while (PIOS_COM_ReceiveBuffer(gpsPort, &c, 1, xDelay) > 0) + { + + // detect start while acquiring stream + if (!start_flag && (c == '$')) { - uint8_t c; - PIOS_COM_ReceiveBuffer(gpsPort, &c, 1, 0); + start_flag = true; + found_cr = false; + rx_count = 0; + } + else + if (!start_flag) + continue; + + if (rx_count >= NMEA_MAX_PACKET_LENGTH) + { + // The buffer is already full and we haven't found a valid NMEA sentence. + // Flush the buffer and note the overflow event. + gpsRxOverflow++; + start_flag = false; + found_cr = false; + rx_count = 0; + } + else + { + gps_rx_buffer[rx_count] = c; + rx_count++; + } + + // look for ending '\r\n' sequence + if (!found_cr && (c == '\r') ) + found_cr = true; + else + if (found_cr && (c != '\n') ) + found_cr = false; // false end flag + else + if (found_cr && (c == '\n') ) + { + // The NMEA functions require a zero-terminated string + // As we detected \r\n, the string as for sure 2 bytes long, we will also strip the \r\n + gps_rx_buffer[rx_count-2] = 0; - if (GTOP_BIN_update_position(c, &numChecksumErrors, &numParsingErrors) >= 0) - { - numUpdates++; + // prepare to parse next sentence + start_flag = false; + found_cr = false; + rx_count = 0; + // Our rxBuffer must look like this now: + // [0] = '$' + // ... = zero or more bytes of sentence payload + // [end_pos - 1] = '\r' + // [end_pos] = '\n' + // + // Prepare to consume the sentence from the buffer + + // Validate the checksum over the sentence + if (!NMEA_checksum(&gps_rx_buffer[1])) + { // Invalid checksum. May indicate dropped characters on Rx. + //PIOS_DEBUG_PinHigh(2); + ++numChecksumErrors; + //PIOS_DEBUG_PinLow(2); + } + else + { // Valid checksum, use this packet to update the GPS position + if (!NMEA_update_position(&gps_rx_buffer[1])) { + //PIOS_DEBUG_PinHigh(2); + ++numParsingErrors; + //PIOS_DEBUG_PinLow(2); + } + else + ++numUpdates; timeNowMs = xTaskGetTickCount() * portTICK_RATE_MS; timeOfLastUpdateMs = timeNowMs; timeOfLastCommandMs = timeNowMs; } } - - #else - // NMEA or SINGLE-SENTENCE GPS mode - - // This blocks the task until there is something on the buffer - while (PIOS_COM_ReceiveBufferUsed(gpsPort) > 0) - { - uint8_t c; - PIOS_COM_ReceiveBuffer(gpsPort, &c, 1, 0); - - // detect start while acquiring stream - if (!start_flag && (c == '$')) - { - start_flag = true; - found_cr = false; - rx_count = 0; - } - else - if (!start_flag) - continue; - - if (rx_count >= sizeof(gps_rx_buffer)) - { - // The buffer is already full and we haven't found a valid NMEA sentence. - // Flush the buffer and note the overflow event. - gpsRxOverflow++; - start_flag = false; - found_cr = false; - rx_count = 0; - } - else - { - gps_rx_buffer[rx_count] = c; - rx_count++; - } - - // look for ending '\r\n' sequence - if (!found_cr && (c == '\r') ) - found_cr = true; - else - if (found_cr && (c != '\n') ) - found_cr = false; // false end flag - else - if (found_cr && (c == '\n') ) - { - // The NMEA functions require a zero-terminated string - // As we detected \r\n, the string as for sure 2 bytes long, we will also strip the \r\n - gps_rx_buffer[rx_count-2] = 0; - - // prepare to parse next sentence - start_flag = false; - found_cr = false; - rx_count = 0; - // Our rxBuffer must look like this now: - // [0] = '$' - // ... = zero or more bytes of sentence payload - // [end_pos - 1] = '\r' - // [end_pos] = '\n' - // - // Prepare to consume the sentence from the buffer - - // Validate the checksum over the sentence - if (!NMEA_checksum(&gps_rx_buffer[1])) - { // Invalid checksum. May indicate dropped characters on Rx. - //PIOS_DEBUG_PinHigh(2); - ++numChecksumErrors; - //PIOS_DEBUG_PinLow(2); - } - else - { // Valid checksum, use this packet to update the GPS position - if (!NMEA_update_position(&gps_rx_buffer[1])) { - //PIOS_DEBUG_PinHigh(2); - ++numParsingErrors; - //PIOS_DEBUG_PinLow(2); - } - else - ++numUpdates; - - timeNowMs = xTaskGetTickCount() * portTICK_RATE_MS; - timeOfLastUpdateMs = timeNowMs; - timeOfLastCommandMs = timeNowMs; - } - } - } - #endif + } // Check for GPS timeout timeNowMs = xTaskGetTickCount() * portTICK_RATE_MS; @@ -309,30 +244,6 @@ static void gpsTask(void *parameters) GPSPositionSet(&GpsData); AlarmsSet(SYSTEMALARMS_ALARM_GPS, SYSTEMALARMS_ALARM_ERROR); - if ((timeNowMs - timeOfLastCommandMs) >= GPS_COMMAND_RESEND_TIMEOUT_MS) - { // resend the command .. just incase the gps has only just been plugged in or the gps did not get our last command - timeOfLastCommandMs = timeNowMs; - - #ifdef ENABLE_GPS_BINARY_GTOP - GTOP_BIN_init(); - // switch to binary mode - PIOS_COM_SendStringNonBlocking(gpsPort,"$PGCMD,21,1*6F\r\n"); - #endif - - #ifdef ENABLE_GPS_ONESENTENCE_GTOP - // switch to single sentence mode - PIOS_COM_SendStringNonBlocking(gpsPort,"$PGCMD,21,2*6C\r\n"); - #endif - - #ifdef ENABLE_GPS_NMEA - // switch to NMEA mode - PIOS_COM_SendStringNonBlocking(gpsPort,"$PGCMD,21,3*6D\r\n"); - #endif - - #ifdef DISABLE_GPS_TRESHOLD - PIOS_COM_SendStringNonBlocking(gpsPort,"$PMTK397,0*23\r\n"); - #endif - } } else { // we appear to be receiving GPS sentences OK, we've had an update @@ -358,8 +269,6 @@ static void gpsTask(void *parameters) AlarmsSet(SYSTEMALARMS_ALARM_GPS, SYSTEMALARMS_ALARM_CRITICAL); } - // Block task until next update - vTaskDelay(xDelay); } } diff --git a/flight/Modules/GPS/GTOP_BIN.c b/flight/Modules/GPS/GTOP_BIN.c deleted file mode 100644 index 7bd2964d9..000000000 --- a/flight/Modules/GPS/GTOP_BIN.c +++ /dev/null @@ -1,262 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotModules OpenPilot Modules - * @{ - * @addtogroup GSPModule GPS Module - * @brief Process GPS information - * @{ - * - * @file GTOP_BIN.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief GPS module, handles GPS and NMEA stream - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "openpilot.h" -#include "pios.h" -#include "GTOP_BIN.h" -#include "gpsposition.h" -#include "gpstime.h" -#include "gpssatellites.h" - -#include // memmove - -#ifdef ENABLE_GPS_BINARY_GTOP - -// ************ -// the structure of the binary packet - -typedef struct -{ - uint32_t utc_time; - - int32_t latitude; - uint8_t ns_indicator; - - int32_t longitude; - uint8_t ew_indicator; - - uint8_t fix_quality; - - uint8_t satellites_used; - - uint16_t hdop; - - int32_t msl_altitude; - - int32_t geoidal_seperation; - - uint8_t fix_type; - - int32_t course_over_ground; - - int32_t speed_over_ground; - - uint8_t day; - uint8_t month; - uint16_t year; -} __attribute__((__packed__)) t_gps_bin_packet_data; - -typedef struct -{ - uint16_t header; - t_gps_bin_packet_data data; - uint8_t asterisk; - uint8_t checksum; - uint16_t end_word; -} __attribute__((__packed__)) t_gps_bin_packet; - -// ************ - -// buffer that holds the incoming binary packet -static uint8_t gps_rx_buffer[sizeof(t_gps_bin_packet)] __attribute__ ((aligned(4))); - -// number of bytes currently in the rx buffer -static int16_t gps_rx_buffer_wr = 0; - -// ************ -// endian swapping functions - -static uint16_t swap2Bytes(uint16_t data) -{ - return (((data >> 8) & 0x00ff) | - ((data << 8) & 0xff00)); -} - -static uint32_t swap4Bytes(uint32_t data) -{ - return (((data >> 24) & 0x000000ff) | - ((data >> 8) & 0x0000ff00) | - ((data << 8) & 0x00ff0000) | - ((data << 24) & 0xff000000)); -} - -// ************ -/** - * Parses a complete binary packet and update the GPSPosition and GPSTime UAVObjects - * - * param[in] .. b = a new received byte from the GPS - * - * return '0' if we have found a valid binary packet - * return <0 if any errors were encountered with the packet or no packet found - */ - -int GTOP_BIN_update_position(uint8_t b, volatile uint32_t *chksum_errors, volatile uint32_t *parsing_errors) -{ - if (gps_rx_buffer_wr >= sizeof(gps_rx_buffer)) - { // make room for the new byte .. this will actually never get executed, just here as a safe guard really - memmove(gps_rx_buffer, gps_rx_buffer + 1, sizeof(gps_rx_buffer) - 1); - gps_rx_buffer_wr = sizeof(gps_rx_buffer) - 1; - } - - // add the new byte into the buffer - gps_rx_buffer[gps_rx_buffer_wr++] = b; - - int16_t i = 0; - - while (gps_rx_buffer_wr > 0) - { - t_gps_bin_packet *rx_packet = (t_gps_bin_packet *)(gps_rx_buffer + i); - - // scan for the start of a binary packet (the header bytes) - while (gps_rx_buffer_wr - i >= sizeof(rx_packet->header)) - { - if (rx_packet->header == 0x2404) - break; // found a valid header marker - rx_packet = (t_gps_bin_packet *)(gps_rx_buffer + ++i); - } - - // remove unwanted bytes before the start of the packet header - if (i > 0) - { - gps_rx_buffer_wr -= i; - if (gps_rx_buffer_wr > 0) - memmove(gps_rx_buffer, gps_rx_buffer + i, gps_rx_buffer_wr); - i = 0; - } - - if (gps_rx_buffer_wr < sizeof(t_gps_bin_packet)) - break; // not yet enough bytes for a complete binary packet - - // we have enough bytes for a complete binary packet - - // check to see if certain parameters in the binary packet are valid - if (rx_packet->header != 0x2404 || - rx_packet->end_word != 0x0A0D || - rx_packet->asterisk != 0x2A || - (rx_packet->data.ns_indicator != 1 && rx_packet->data.ns_indicator != 2) || - (rx_packet->data.ew_indicator != 1 && rx_packet->data.ew_indicator != 2) || - (rx_packet->data.fix_quality > 2) || - (rx_packet->data.fix_type < 1 || rx_packet->data.fix_type > 3) ) - { // invalid packet - if (parsing_errors) *parsing_errors++; - i++; - continue; - } - - { // check the checksum is valid - uint8_t *p = (uint8_t *)&rx_packet->data; - uint8_t checksum = 0; - for (int i = 0; i < sizeof(t_gps_bin_packet_data); i++) - checksum ^= *p++; - - if (checksum != rx_packet->checksum) - { // checksum error - if (chksum_errors) *chksum_errors++; - i++; - continue; - } - } - - // we now have a valid complete binary packet, update the GpsData and GpsTime objects - - // correct the endian order of the parameters - rx_packet->data.utc_time = swap4Bytes(rx_packet->data.utc_time); - rx_packet->data.latitude = swap4Bytes(rx_packet->data.latitude); - rx_packet->data.longitude = swap4Bytes(rx_packet->data.longitude); - rx_packet->data.hdop = swap2Bytes(rx_packet->data.hdop); - rx_packet->data.msl_altitude = swap4Bytes(rx_packet->data.msl_altitude); - rx_packet->data.geoidal_seperation = swap4Bytes(rx_packet->data.geoidal_seperation); - rx_packet->data.course_over_ground = swap4Bytes(rx_packet->data.course_over_ground); - rx_packet->data.speed_over_ground = swap4Bytes(rx_packet->data.speed_over_ground); - rx_packet->data.year = swap2Bytes(rx_packet->data.year); - - // set the gps time object - GPSTimeData GpsTime; -// GPSTimeGet(&GpsTime); - uint32_t utc_time = rx_packet->data.utc_time / 1000; - GpsTime.Second = utc_time % 100; // seconds - GpsTime.Minute = (utc_time / 100) % 100; // minutes - GpsTime.Hour = utc_time / 10000; // hours - GpsTime.Day = rx_packet->data.day; // day - GpsTime.Month = rx_packet->data.month; // month - GpsTime.Year = rx_packet->data.year; // year - GPSTimeSet(&GpsTime); - - // set the gps position object - GPSPositionData GpsData; -// GPSPositionGet(&GpsData); - switch (rx_packet->data.fix_type) - { - case 1: GpsData.Status = GPSPOSITION_STATUS_NOFIX; break; - case 2: GpsData.Status = GPSPOSITION_STATUS_FIX2D; break; - case 3: GpsData.Status = GPSPOSITION_STATUS_FIX3D; break; - default: GpsData.Status = GPSPOSITION_STATUS_NOGPS; break; - } - GpsData.Latitude = rx_packet->data.latitude * (rx_packet->data.ns_indicator == 1 ? +1 : -1) * 10; // degrees * 10e6 - GpsData.Longitude = rx_packet->data.longitude * (rx_packet->data.ew_indicator == 1 ? +1 : -1) * 10; // degrees * 10e6 - GpsData.Altitude = (float)rx_packet->data.msl_altitude / 1000; // meters - GpsData.GeoidSeparation = (float)rx_packet->data.geoidal_seperation / 1000; // meters - GpsData.Heading = (float)rx_packet->data.course_over_ground / 1000; // degrees - GpsData.Groundspeed = (float)rx_packet->data.speed_over_ground / 3600; // m/s - GpsData.Satellites = rx_packet->data.satellites_used; // - GpsData.PDOP = 99.99; // not available in binary mode - GpsData.HDOP = (float)rx_packet->data.hdop / 100; // - GpsData.VDOP = 99.99; // not available in binary mode - GPSPositionSet(&GpsData); - - // set the number of satellites -// GPSSatellitesData SattelliteData; -//// GPSSatellitesGet(&SattelliteData); -// memset(&SattelliteData, 0, sizeof(SattelliteData)); -// SattelliteData.SatsInView = rx_packet->data.satellites_used; // -// GPSSatellitesSet(&SattelliteData); - - // remove the spent binary packet from the buffer - gps_rx_buffer_wr -= sizeof(t_gps_bin_packet); - if (gps_rx_buffer_wr > 0) - memmove(gps_rx_buffer, gps_rx_buffer + sizeof(t_gps_bin_packet), gps_rx_buffer_wr); - - return 0; // found a valid packet - } - - return -1; // no valid packet found -} - -// ************ - -void GTOP_BIN_init(void) -{ - gps_rx_buffer_wr = 0; -} - -// ************ - -#endif // ENABLE_GPS_BINARY_GTOP - diff --git a/flight/Modules/GPS/NMEA.c b/flight/Modules/GPS/NMEA.c index 3dfd98d40..adadc588a 100644 --- a/flight/Modules/GPS/NMEA.c +++ b/flight/Modules/GPS/NMEA.c @@ -40,8 +40,6 @@ -#if defined(ENABLE_GPS_NMEA) || defined(ENABLE_GPS_ONESENTENCE_GTOP) - // Debugging #ifdef ENABLE_DEBUG_MSG //#define DEBUG_MSG_IN ///< define to display the incoming NMEA messages @@ -54,7 +52,6 @@ //#define NMEA_DEBUG_GSA ///< define to enable debug of GSA messages //#define NMEA_DEBUG_GSV ///< define to enable debug of GSV messages //#define NMEA_DEBUG_ZDA ///< define to enable debug of ZDA messages -//#define NMEA_DEBUG_PGTOP ///< define to enable debug of PGTOP messages #define DEBUG_MSG(format, ...) PIOS_COM_SendFormattedString(DEBUG_PORT, format, ## __VA_ARGS__) #else #define DEBUG_MSG(format, ...) @@ -69,56 +66,45 @@ struct nmea_parser { uint32_t cnt; }; - #ifdef ENABLE_GPS_NMEA - static bool nmeaProcessGPGGA(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam); - static bool nmeaProcessGPRMC(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam); - static bool nmeaProcessGPVTG(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam); - static bool nmeaProcessGPGSA(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam); - static bool nmeaProcessGPZDA(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam); - static bool nmeaProcessGPGSV(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam); - #endif +static bool nmeaProcessGPGGA(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam); +static bool nmeaProcessGPRMC(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam); +static bool nmeaProcessGPVTG(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam); +static bool nmeaProcessGPGSA(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam); +static bool nmeaProcessGPZDA(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam); +static bool nmeaProcessGPGSV(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam); - static bool nmeaProcessPGTOP(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam); - static struct nmea_parser nmea_parsers[] = { - - #ifdef ENABLE_GPS_NMEA - { - .prefix = "GPGGA", - .handler = nmeaProcessGPGGA, - .cnt = 0, - }, - { - .prefix = "GPVTG", - .handler = nmeaProcessGPVTG, - .cnt = 0, - }, - { - .prefix = "GPGSA", - .handler = nmeaProcessGPGSA, - .cnt = 0, - }, - { - .prefix = "GPRMC", - .handler = nmeaProcessGPRMC, - .cnt = 0, - }, - { - .prefix = "GPZDA", - .handler = nmeaProcessGPZDA, - .cnt = 0, - }, - { - .prefix = "GPGSV", - .handler = nmeaProcessGPGSV, - .cnt = 0, - }, - #endif - { - .prefix = "PGTOP", - .handler = nmeaProcessPGTOP, - .cnt = 0, - }, +static struct nmea_parser nmea_parsers[] = { + { + .prefix = "GPGGA", + .handler = nmeaProcessGPGGA, + .cnt = 0, + }, + { + .prefix = "GPVTG", + .handler = nmeaProcessGPVTG, + .cnt = 0, + }, + { + .prefix = "GPGSA", + .handler = nmeaProcessGPGSA, + .cnt = 0, + }, + { + .prefix = "GPRMC", + .handler = nmeaProcessGPRMC, + .cnt = 0, + }, + { + .prefix = "GPZDA", + .handler = nmeaProcessGPZDA, + .cnt = 0, + }, + { + .prefix = "GPGSV", + .handler = nmeaProcessGPGSV, + .cnt = 0, + }, }; static struct nmea_parser *NMEA_find_parser_by_prefix(const char *prefix) @@ -229,7 +215,6 @@ static float NMEA_real_to_float(char *nmea_real) return (((float)whole) + fract * pow(10, -fract_units)); } -#ifdef ENABLE_GPS_NMEA /* * Parse a field in the format: * DD[D]MM.mmmm[mm] @@ -287,7 +272,6 @@ static bool NMEA_latlon_to_fixed_point(int32_t * latlon, char *nmea_latlon, bool return true; } -#endif // ENABLE_GPS_NMEA /** @@ -376,7 +360,6 @@ bool NMEA_update_position(char *nmea_sentence) return true; } -#ifdef ENABLE_GPS_NMEA /** * Parse an NMEA GPGGA sentence and update the given UAVObject @@ -675,83 +658,3 @@ static bool nmeaProcessGPGSA(GPSPositionData * GpsData, bool* gpsDataUpdated, ch return true; } -#endif // ENABLE_GPS_NMEA - -/** - * Parse an NMEA PGTOP sentence and update the given UAVObject - * \param[in] A pointer to a GPSPosition UAVObject to be updated. - * \param[in] An NMEA sentence with a valid checksum - */ -static bool nmeaProcessPGTOP(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam) -{ - if (nbParam != 17) - return false; - - GPSTimeData gpst; - GPSTimeGet(&gpst); - - *gpsDataUpdated = true; - - // get UTC time [hhmmss.sss] - float hms = NMEA_real_to_float(param[1]); - gpst.Second = (int)hms % 100; - gpst.Minute = (((int)hms - gpst.Second) / 100) % 100; - gpst.Hour = (int)hms / 10000; - - // get latitude decimal degrees - GpsData->Latitude = NMEA_real_to_float(param[2])*1e7; - if (param[3][0] == 'S') - GpsData->Latitude = -GpsData->Latitude; - - - // get longitude decimal degrees - GpsData->Longitude = NMEA_real_to_float(param[4])*1e7; - if (param[5][0] == 'W') - GpsData->Longitude = -GpsData->Longitude; - - // get number of satellites used in GPS solution - GpsData->Satellites = atoi(param[7]); - - // next field: HDOP - GpsData->HDOP = NMEA_real_to_float(param[8]); - - // get altitude (in meters mm.m) - GpsData->Altitude = NMEA_real_to_float(param[9]); - - // next field: geoid separation - GpsData->GeoidSeparation = NMEA_real_to_float(param[10]); - - // Mode: 1=Fix not available, 2=2D, 3=3D - switch (atoi(param[11])) { - case 1: - GpsData->Status = GPSPOSITION_STATUS_NOFIX; - break; - case 2: - GpsData->Status = GPSPOSITION_STATUS_FIX2D; - break; - case 3: - GpsData->Status = GPSPOSITION_STATUS_FIX3D; - break; - default: - /* Unhandled */ - return false; - break; - } - - // get course over ground in degrees [ddd.dd] - GpsData->Heading = NMEA_real_to_float(param[12]); - - // get speed in km/h - GpsData->Groundspeed = NMEA_real_to_float(param[13]); - // to m/s - GpsData->Groundspeed /= 3.6; - - gpst.Day = atoi(param[14]); - gpst.Month = atoi(param[15]); - gpst.Year = atoi(param[16]); - GPSTimeSet(&gpst); - - return true; -} - -#endif // #if defined(ENABLE_GPS_NMEA) || defined(ENABLE_GPS_ONESENTENCE_GTOP) diff --git a/flight/Modules/GPS/inc/GPS.h b/flight/Modules/GPS/inc/GPS.h index 1ae683c9a..86a92d285 100644 --- a/flight/Modules/GPS/inc/GPS.h +++ b/flight/Modules/GPS/inc/GPS.h @@ -34,8 +34,6 @@ #ifndef GPS_H #define GPS_H -#include "gps_mode.h" - int32_t GPSInitialize(void); #endif // GPS_H diff --git a/flight/Modules/GPS/inc/NMEA.h b/flight/Modules/GPS/inc/NMEA.h index 5c1b13f8b..6ff6b1195 100644 --- a/flight/Modules/GPS/inc/NMEA.h +++ b/flight/Modules/GPS/inc/NMEA.h @@ -33,11 +33,8 @@ #include #include -#include "gps_mode.h" -#if defined(ENABLE_GPS_NMEA) || defined(ENABLE_GPS_ONESENTENCE_GTOP) - extern bool NMEA_update_position(char *nmea_sentence); - extern bool NMEA_checksum(char *nmea_sentence); -#endif +extern bool NMEA_update_position(char *nmea_sentence); +extern bool NMEA_checksum(char *nmea_sentence); #endif /* NMEA_H */ diff --git a/flight/Modules/GPS/inc/gps_mode.h b/flight/Modules/GPS/inc/gps_mode.h deleted file mode 100644 index 43e5b0398..000000000 --- a/flight/Modules/GPS/inc/gps_mode.h +++ /dev/null @@ -1,58 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotModules OpenPilot Modules - * @{ - * @addtogroup GSPModule GPS Module - * @brief Process GPS information - * @{ - * - * @file gps_mode.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Include file of the GPS module. - * As with all modules only the initialize function is exposed all other - * interactions with the module take place through the event queue and - * objects. - * @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 GPS_MODE_H -#define GPS_MODE_H - -// **************** -// you MUST have one of these uncommented - and ONLY one - -//#define ENABLE_GPS_BINARY_GTOP // uncomment this if we are using GTOP BINARY mode -//#define ENABLE_GPS_ONESENTENCE_GTOP // uncomment this if we are using GTOP SINGLE SENTENCE mode -#define ENABLE_GPS_NMEA // uncomment this if we are using NMEA mode - -// **************** -// make sure they have defined a protocol to use - -#if !defined(ENABLE_GPS_BINARY_GTOP) && !defined(ENABLE_GPS_ONESENTENCE_GTOP) && !defined(ENABLE_GPS_NMEA) - #error YOU MUST SELECT THE DESIRED GPS PROTOCOL IN gps_mode.h! -#endif - -// **************** - -#endif - -/** - * @} - * @} - */ diff --git a/flight/Modules/ManualControl/manualcontrol.c b/flight/Modules/ManualControl/manualcontrol.c index ba47fd64b..eab3605be 100644 --- a/flight/Modules/ManualControl/manualcontrol.c +++ b/flight/Modules/ManualControl/manualcontrol.c @@ -43,6 +43,7 @@ #include "flighttelemetrystats.h" #include "flightstatus.h" #include "accessorydesired.h" +#include "receiveractivity.h" // Private constants #if defined(PIOS_MANUAL_STACK_SIZE) @@ -80,6 +81,7 @@ static void updateActuatorDesired(ManualControlCommandData * cmd); static void updateStabilizationDesired(ManualControlCommandData * cmd, ManualControlSettingsData * settings); static void processFlightMode(ManualControlSettingsData * settings, float flightMode); static void processArm(ManualControlCommandData * cmd, ManualControlSettingsData * settings); +static void setArmedIfChanged(uint8_t val); static void manualControlTask(void *parameters); static float scaleChannel(int16_t value, int16_t max, int16_t min, int16_t neutral); @@ -87,6 +89,18 @@ static uint32_t timeDifferenceMs(portTickType start_time, portTickType end_time) static bool okToArm(void); static bool validInputRange(int16_t min, int16_t max, uint16_t value); +#define RCVR_ACTIVITY_MONITOR_CHANNELS_PER_GROUP 12 +#define RCVR_ACTIVITY_MONITOR_MIN_RANGE 10 +struct rcvr_activity_fsm { + ManualControlSettingsChannelGroupsOptions group; + uint16_t prev[RCVR_ACTIVITY_MONITOR_CHANNELS_PER_GROUP]; + uint8_t sample_count; +}; +static struct rcvr_activity_fsm activity_fsm; + +static void resetRcvrActivity(struct rcvr_activity_fsm * fsm); +static bool updateRcvrActivity(struct rcvr_activity_fsm * fsm); + #define assumptions (assumptions1 && assumptions3 && assumptions5 && assumptions7 && assumptions8 && assumptions_flightmode) /** @@ -116,7 +130,7 @@ int32_t ManualControlInitialize() ManualControlCommandInitialize(); FlightStatusInitialize(); StabilizationDesiredInitialize(); - + ReceiverActivityInitialize(); ManualControlSettingsInitialize(); return 0; @@ -147,10 +161,14 @@ static void manualControlTask(void *parameters) flightStatus.Armed = FLIGHTSTATUS_ARMED_DISARMED; armState = ARM_STATE_DISARMED; + /* Initialize the RcvrActivty FSM */ + portTickType lastActivityTime = xTaskGetTickCount(); + resetRcvrActivity(&activity_fsm); + // Main task loop lastSysTime = xTaskGetTickCount(); while (1) { - float scaledChannel[MANUALCONTROLCOMMAND_CHANNEL_NUMELEM]; + float scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_NUMELEM]; // Wait until next update vTaskDelayUntil(&lastSysTime, UPDATE_PERIOD_MS / portTICK_RATE_MS); @@ -159,6 +177,18 @@ static void manualControlTask(void *parameters) // Read settings ManualControlSettingsGet(&settings); + /* Update channel activity monitor */ + if (flightStatus.Armed == ARM_STATE_DISARMED) { + if (updateRcvrActivity(&activity_fsm)) { + /* Reset the aging timer because activity was detected */ + lastActivityTime = lastSysTime; + } + } + if (timeDifferenceMs(lastActivityTime, lastSysTime) > 5000) { + resetRcvrActivity(&activity_fsm); + lastActivityTime = lastSysTime; + } + if (ManualControlCommandReadOnly(&cmd)) { FlightTelemetryStatsData flightTelemStats; FlightTelemetryStatsGet(&flightTelemStats); @@ -173,34 +203,64 @@ static void manualControlTask(void *parameters) if (!ManualControlCommandReadOnly(&cmd)) { + bool valid_input_detected = true; + // Read channel values in us - for (int n = 0; n < MANUALCONTROLCOMMAND_CHANNEL_NUMELEM; ++n) { - if (pios_rcvr_channel_to_id_map[n].id) { - cmd.Channel[n] = PIOS_RCVR_Read(pios_rcvr_channel_to_id_map[n].id, - pios_rcvr_channel_to_id_map[n].channel); + for (uint8_t n = 0; + n < MANUALCONTROLSETTINGS_CHANNELGROUPS_NUMELEM && n < MANUALCONTROLCOMMAND_CHANNEL_NUMELEM; + ++n) { + extern uint32_t pios_rcvr_group_map[]; + + if (settings.ChannelGroups[n] >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE) { + cmd.Channel[n] = PIOS_RCVR_INVALID; } else { - cmd.Channel[n] = -1; + cmd.Channel[n] = PIOS_RCVR_Read(pios_rcvr_group_map[settings.ChannelGroups[n]], + settings.ChannelNumber[n]); } - scaledChannel[n] = scaleChannel(cmd.Channel[n], settings.ChannelMax[n], settings.ChannelMin[n], settings.ChannelNeutral[n]); + + // If a channel has timed out this is not valid data and we shouldn't update anything + // until we decide to go to failsafe + if(cmd.Channel[n] == PIOS_RCVR_TIMEOUT) + valid_input_detected = false; + else + scaledChannel[n] = scaleChannel(cmd.Channel[n], settings.ChannelMax[n], settings.ChannelMin[n], settings.ChannelNeutral[n]); } // Check settings, if error raise alarm - if (settings.Roll >= MANUALCONTROLSETTINGS_ROLL_NONE || - settings.Pitch >= MANUALCONTROLSETTINGS_PITCH_NONE || - settings.Yaw >= MANUALCONTROLSETTINGS_YAW_NONE || - settings.Throttle >= MANUALCONTROLSETTINGS_THROTTLE_NONE || - settings.FlightMode >= MANUALCONTROLSETTINGS_FLIGHTMODE_NONE) { + if (settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_ROLL] >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE || + settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_PITCH] >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE || + settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_YAW] >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE || + settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_THROTTLE] >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE || + settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_FLIGHTMODE] >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE || + // Check all channel mappings are valid + cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_ROLL] == (uint16_t) PIOS_RCVR_INVALID || + cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_PITCH] == (uint16_t) PIOS_RCVR_INVALID || + cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_YAW] == (uint16_t) PIOS_RCVR_INVALID || + cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_THROTTLE] == (uint16_t) PIOS_RCVR_INVALID || + cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_FLIGHTMODE] == (uint16_t) PIOS_RCVR_INVALID || + // Check the driver is exists + cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_ROLL] == (uint16_t) PIOS_RCVR_NODRIVER || + cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_PITCH] == (uint16_t) PIOS_RCVR_NODRIVER || + cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_YAW] == (uint16_t) PIOS_RCVR_NODRIVER || + cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_THROTTLE] == (uint16_t) PIOS_RCVR_NODRIVER || + cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_FLIGHTMODE] == (uint16_t) PIOS_RCVR_NODRIVER) { + AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_CRITICAL); cmd.Connected = MANUALCONTROLCOMMAND_CONNECTED_FALSE; ManualControlCommandSet(&cmd); + + // Need to do this here since we don't process armed status. Since this shouldn't happen in flight (changed config) + // immediately disarm + setArmedIfChanged(FLIGHTSTATUS_ARMED_DISARMED); + continue; } // decide if we have valid manual input or not - bool valid_input_detected = validInputRange(settings.ChannelMin[settings.Throttle], settings.ChannelMax[settings.Throttle], cmd.Channel[settings.Throttle]) && - validInputRange(settings.ChannelMin[settings.Roll], settings.ChannelMax[settings.Roll], cmd.Channel[settings.Roll]) && - validInputRange(settings.ChannelMin[settings.Yaw], settings.ChannelMax[settings.Yaw], cmd.Channel[settings.Yaw]) && - validInputRange(settings.ChannelMin[settings.Pitch], settings.ChannelMax[settings.Pitch], cmd.Channel[settings.Pitch]); + valid_input_detected &= validInputRange(settings.ChannelMin[MANUALCONTROLSETTINGS_CHANNELGROUPS_THROTTLE], settings.ChannelMax[MANUALCONTROLSETTINGS_CHANNELGROUPS_THROTTLE], cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_THROTTLE]) && + validInputRange(settings.ChannelMin[MANUALCONTROLSETTINGS_CHANNELGROUPS_ROLL], settings.ChannelMax[MANUALCONTROLSETTINGS_CHANNELGROUPS_ROLL], cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_ROLL]) && + validInputRange(settings.ChannelMin[MANUALCONTROLSETTINGS_CHANNELGROUPS_YAW], settings.ChannelMax[MANUALCONTROLSETTINGS_CHANNELGROUPS_YAW], cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_YAW]) && + validInputRange(settings.ChannelMin[MANUALCONTROLSETTINGS_CHANNELGROUPS_PITCH], settings.ChannelMax[MANUALCONTROLSETTINGS_CHANNELGROUPS_PITCH], cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_PITCH]); // Implement hysteresis loop on connection status if (valid_input_detected && (++connected_count > 10)) { @@ -222,51 +282,78 @@ static void manualControlTask(void *parameters) // Important: Throttle < 0 will reset Stabilization coefficients among other things. Either change this, // or leave throttle at IDLE speed or above when going into AUTO-failsafe. AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_WARNING); - ManualControlCommandSet(&cmd); - } else { - AlarmsClear(SYSTEMALARMS_ALARM_MANUALCONTROL); - - // Scale channels to -1 -> +1 range - cmd.Roll = scaledChannel[settings.Roll]; - cmd.Pitch = scaledChannel[settings.Pitch]; - cmd.Yaw = scaledChannel[settings.Yaw]; - cmd.Throttle = scaledChannel[settings.Throttle]; - flightMode = scaledChannel[settings.FlightMode]; - + AccessoryDesiredData accessory; // Set Accessory 0 - if(settings.Accessory0 != MANUALCONTROLSETTINGS_ACCESSORY0_NONE) { - accessory.AccessoryVal = scaledChannel[settings.Accessory0]; + if (settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_ACCESSORY0] != + MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE) { + accessory.AccessoryVal = 0; if(AccessoryDesiredInstSet(0, &accessory) != 0) AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_WARNING); } // Set Accessory 1 - if(settings.Accessory1 != MANUALCONTROLSETTINGS_ACCESSORY1_NONE) { - accessory.AccessoryVal = scaledChannel[settings.Accessory1]; + if (settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_ACCESSORY1] != + MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE) { + accessory.AccessoryVal = 0; if(AccessoryDesiredInstSet(1, &accessory) != 0) AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_WARNING); } - // Set Accsesory 2 - if(settings.Accessory2 != MANUALCONTROLSETTINGS_ACCESSORY2_NONE) { - accessory.AccessoryVal = scaledChannel[settings.Accessory2]; + // Set Accessory 2 + if (settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_ACCESSORY2] != + MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE) { + accessory.AccessoryVal = 0; + if(AccessoryDesiredInstSet(2, &accessory) != 0) + AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_WARNING); + } + + } else { + AlarmsClear(SYSTEMALARMS_ALARM_MANUALCONTROL); + + // Scale channels to -1 -> +1 range + cmd.Roll = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_ROLL]; + cmd.Pitch = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_PITCH]; + cmd.Yaw = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_YAW]; + cmd.Throttle = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_THROTTLE]; + flightMode = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_FLIGHTMODE]; + + AccessoryDesiredData accessory; + // Set Accessory 0 + if (settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_ACCESSORY0] != + MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE) { + accessory.AccessoryVal = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_ACCESSORY0]; + if(AccessoryDesiredInstSet(0, &accessory) != 0) + AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_WARNING); + } + // Set Accessory 1 + if (settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_ACCESSORY1] != + MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE) { + accessory.AccessoryVal = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_ACCESSORY1]; + if(AccessoryDesiredInstSet(1, &accessory) != 0) + AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_WARNING); + } + // Set Accessory 2 + if (settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_ACCESSORY2] != + MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE) { + accessory.AccessoryVal = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_ACCESSORY2]; if(AccessoryDesiredInstSet(2, &accessory) != 0) AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_WARNING); } processFlightMode(&settings, flightMode); - processArm(&cmd, &settings); - - // Update cmd object - ManualControlCommandSet(&cmd); } + // Process arming outside conditional so system will disarm when disconnected + processArm(&cmd, &settings); + + // Update cmd object + ManualControlCommandSet(&cmd); + } else { ManualControlCommandGet(&cmd); /* Under GCS control */ } - FlightStatusGet(&flightStatus); // Depending on the mode update the Stabilization or Actuator objects @@ -288,6 +375,144 @@ static void manualControlTask(void *parameters) } } +static void resetRcvrActivity(struct rcvr_activity_fsm * fsm) +{ + ReceiverActivityData data; + bool updated = false; + + /* Clear all channel activity flags */ + ReceiverActivityGet(&data); + if (data.ActiveGroup != RECEIVERACTIVITY_ACTIVEGROUP_NONE && + data.ActiveChannel != 255) { + data.ActiveGroup = RECEIVERACTIVITY_ACTIVEGROUP_NONE; + data.ActiveChannel = 255; + updated = true; + } + if (updated) { + ReceiverActivitySet(&data); + } + + /* Reset the FSM state */ + fsm->group = 0; + fsm->sample_count = 0; +} + +static void updateRcvrActivitySample(uint32_t rcvr_id, uint16_t samples[], uint8_t max_channels) { + for (uint8_t channel = 0; channel < max_channels; channel++) { + samples[channel] = PIOS_RCVR_Read(rcvr_id, channel); + } +} + +static bool updateRcvrActivityCompare(uint32_t rcvr_id, struct rcvr_activity_fsm * fsm) +{ + bool activity_updated = false; + + /* Compare the current value to the previous sampled value */ + for (uint8_t channel = 0; + channel < RCVR_ACTIVITY_MONITOR_CHANNELS_PER_GROUP; + channel++) { + uint16_t delta; + uint16_t prev = fsm->prev[channel]; + uint16_t curr = PIOS_RCVR_Read(rcvr_id, channel); + if (curr > prev) { + delta = curr - prev; + } else { + delta = prev - curr; + } + + if (delta > RCVR_ACTIVITY_MONITOR_MIN_RANGE) { + /* Mark this channel as active */ + ReceiverActivityActiveGroupOptions group; + + /* Don't assume manualcontrolsettings and receiveractivity are in the same order. */ + switch (fsm->group) { + case MANUALCONTROLSETTINGS_CHANNELGROUPS_PWM: + group = RECEIVERACTIVITY_ACTIVEGROUP_PWM; + break; + case MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM: + group = RECEIVERACTIVITY_ACTIVEGROUP_PPM; + break; + case MANUALCONTROLSETTINGS_CHANNELGROUPS_SPEKTRUM1: + group = RECEIVERACTIVITY_ACTIVEGROUP_SPEKTRUM1; + break; + case MANUALCONTROLSETTINGS_CHANNELGROUPS_SPEKTRUM2: + group = RECEIVERACTIVITY_ACTIVEGROUP_SPEKTRUM2; + break; + case MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS: + group = RECEIVERACTIVITY_ACTIVEGROUP_SBUS; + break; + case MANUALCONTROLSETTINGS_CHANNELGROUPS_GCS: + group = RECEIVERACTIVITY_ACTIVEGROUP_GCS; + break; + default: + PIOS_Assert(0); + break; + } + + ReceiverActivityActiveGroupSet(&group); + ReceiverActivityActiveChannelSet(&channel); + activity_updated = true; + } + } + return (activity_updated); +} + +static bool updateRcvrActivity(struct rcvr_activity_fsm * fsm) +{ + bool activity_updated = false; + + if (fsm->group >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE) { + /* We're out of range, reset things */ + resetRcvrActivity(fsm); + } + + extern uint32_t pios_rcvr_group_map[]; + if (!pios_rcvr_group_map[fsm->group]) { + /* Unbound group, skip it */ + goto group_completed; + } + + if (fsm->sample_count == 0) { + /* Take a sample of each channel in this group */ + updateRcvrActivitySample(pios_rcvr_group_map[fsm->group], + fsm->prev, + NELEMENTS(fsm->prev)); + fsm->sample_count++; + return (false); + } + + /* Compare with previous sample */ + activity_updated = updateRcvrActivityCompare(pios_rcvr_group_map[fsm->group], fsm); + +group_completed: + /* Reset the sample counter */ + fsm->sample_count = 0; + + /* Find the next active group, but limit search so we can't loop forever here */ + for (uint8_t i = 0; i < MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE; i++) { + /* Move to the next group */ + fsm->group++; + if (fsm->group >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE) { + /* Wrap back to the first group */ + fsm->group = 0; + } + if (pios_rcvr_group_map[fsm->group]) { + /* + * Found an active group, take a sample here to avoid an + * extra 20ms delay in the main thread so we can speed up + * this algorithm. + */ + updateRcvrActivitySample(pios_rcvr_group_map[fsm->group], + fsm->prev, + NELEMENTS(fsm->prev)); + fsm->sample_count++; + break; + } + } + + return (activity_updated); +} + static void updateActuatorDesired(ManualControlCommandData * cmd) { ActuatorDesiredData actuator; @@ -449,7 +674,7 @@ static void processArm(ManualControlCommandData * cmd, ManualControlSettingsData } else { // Not really needed since this function not called when disconnected if (cmd->Connected == MANUALCONTROLCOMMAND_CONNECTED_FALSE) - return; + lowThrottle = true; // The throttle is not low, in case we where arming or disarming, abort if (!lowThrottle) { diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index b4f959f2c..168b46aa6 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -75,7 +75,8 @@ static uint32_t idleCounter; static uint32_t idleCounterClear; static xTaskHandle systemTaskHandle; -static int32_t stackOverflow; +static bool stackOverflow; +static bool mallocFailed; // Private functions static void objectUpdatedCb(UAVObjEvent * ev); @@ -93,7 +94,8 @@ static void updateWDGstats(); int32_t SystemModStart(void) { // Initialize vars - stackOverflow = 0; + stackOverflow = false; + mallocFailed = false; // Create system task xTaskCreate(systemTask, (signed char *)"System", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &systemTaskHandle); // Register task @@ -417,12 +419,19 @@ static void updateSystemAlarms() } // Check for stack overflow - if (stackOverflow == 1) { + if (stackOverflow) { AlarmsSet(SYSTEMALARMS_ALARM_STACKOVERFLOW, SYSTEMALARMS_ALARM_CRITICAL); } else { AlarmsClear(SYSTEMALARMS_ALARM_STACKOVERFLOW); } + // Check for malloc failures + if (mallocFailed) { + AlarmsSet(SYSTEMALARMS_ALARM_OUTOFMEMORY, SYSTEMALARMS_ALARM_CRITICAL); + } else { + AlarmsClear(SYSTEMALARMS_ALARM_OUTOFMEMORY); + } + #if defined(PIOS_INCLUDE_SDCARD) // Check for SD card if (PIOS_SDCARD_IsMounted() == 0) { @@ -461,9 +470,29 @@ void vApplicationIdleHook(void) /** * Called by the RTOS when a stack overflow is detected. */ +#define DEBUG_STACK_OVERFLOW 0 void vApplicationStackOverflowHook(xTaskHandle * pxTask, signed portCHAR * pcTaskName) { - stackOverflow = 1; + stackOverflow = true; +#if DEBUG_STACK_OVERFLOW + static volatile bool wait_here = true; + while(wait_here); + wait_here = true; +#endif +} + +/** + * Called by the RTOS when a malloc call fails. + */ +#define DEBUG_MALLOC_FAILURES 0 +void vApplicationMallocFailedHook(void) +{ + mallocFailed = true; +#if DEBUG_MALLOC_FAILURES + static volatile bool wait_here = true; + while(wait_here); + wait_here = true; +#endif } /** diff --git a/flight/OpenPilot/Makefile b/flight/OpenPilot/Makefile index aaa6a4a46..0da393848 100644 --- a/flight/OpenPilot/Makefile +++ b/flight/OpenPilot/Makefile @@ -163,6 +163,7 @@ SRC += $(PIOSSTM32F10X)/pios_ppm.c SRC += $(PIOSSTM32F10X)/pios_pwm.c SRC += $(PIOSSTM32F10X)/pios_spektrum.c SRC += $(PIOSSTM32F10X)/pios_sbus.c +SRC += $(PIOSSTM32F10X)/pios_tim.c SRC += $(PIOSSTM32F10X)/pios_debug.c SRC += $(PIOSSTM32F10X)/pios_gpio.c SRC += $(PIOSSTM32F10X)/pios_exti.c diff --git a/flight/OpenPilot/System/inc/FreeRTOSConfig.h b/flight/OpenPilot/System/inc/FreeRTOSConfig.h index 48b7c1560..4b37f7e44 100644 --- a/flight/OpenPilot/System/inc/FreeRTOSConfig.h +++ b/flight/OpenPilot/System/inc/FreeRTOSConfig.h @@ -26,6 +26,7 @@ #define configUSE_PREEMPTION 1 #define configUSE_IDLE_HOOK 1 #define configUSE_TICK_HOOK 0 +#define configUSE_MALLOC_FAILED_HOOK 1 #define configCPU_CLOCK_HZ ( ( unsigned long ) 72000000 ) #define configTICK_RATE_HZ ( ( portTickType ) 1000 ) #define configMAX_PRIORITIES ( ( unsigned portBASE_TYPE ) 5 ) diff --git a/flight/OpenPilot/System/inc/pios_config.h b/flight/OpenPilot/System/inc/pios_config.h index 4e6657cef..8e37dc95a 100644 --- a/flight/OpenPilot/System/inc/pios_config.h +++ b/flight/OpenPilot/System/inc/pios_config.h @@ -47,7 +47,7 @@ #define PIOS_INCLUDE_SPEKTRUM //#define PIOS_INCLUDE_SBUS #define PIOS_INCLUDE_PWM -//#define PIOS_INCLUDE_PPM +#define PIOS_INCLUDE_PPM #define PIOS_INCLUDE_TELEMETRY_RF diff --git a/flight/OpenPilot/System/pios_board.c b/flight/OpenPilot/System/pios_board.c index 12d365b67..22bf12cad 100644 --- a/flight/OpenPilot/System/pios_board.c +++ b/flight/OpenPilot/System/pios_board.c @@ -30,6 +30,7 @@ #include #include #include +#include #include "manualcontrolsettings.h" //#define I2C_DEBUG_PIN 0 @@ -301,6 +302,89 @@ void PIOS_ADC_handler() { PIOS_ADC_DMA_Handler(); } +#include "pios_tim_priv.h" + +static const TIM_TimeBaseInitTypeDef tim_4_8_time_base = { + .TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1, + .TIM_ClockDivision = TIM_CKD_DIV1, + .TIM_CounterMode = TIM_CounterMode_Up, + .TIM_Period = ((1000000 / PIOS_SERVO_UPDATE_HZ) - 1), + .TIM_RepetitionCounter = 0x0000, +}; + +static const struct pios_tim_clock_cfg tim_4_cfg = { + .timer = TIM4, + .time_base_init = &tim_4_8_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM4_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_clock_cfg tim_8_cfg = { + .timer = TIM8, + .time_base_init = &tim_4_8_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM8_CC_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const TIM_TimeBaseInitTypeDef tim_1_3_5_time_base = { + .TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1, + .TIM_ClockDivision = TIM_CKD_DIV1, + .TIM_CounterMode = TIM_CounterMode_Up, + .TIM_Period = 0xFFFF, + .TIM_RepetitionCounter = 0x0000, +}; + +static const struct pios_tim_clock_cfg tim_1_cfg = { + .timer = TIM1, + .time_base_init = &tim_1_3_5_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM1_CC_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_clock_cfg tim_3_cfg = { + .timer = TIM3, + .time_base_init = &tim_1_3_5_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM3_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_clock_cfg tim_5_cfg = { + .timer = TIM5, + .time_base_init = &tim_1_3_5_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM5_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + #if defined(PIOS_INCLUDE_USART) #include "pios_usart_priv.h" @@ -496,7 +580,6 @@ static const struct pios_usart_cfg pios_usart_spektrum_cfg = { }, }; -#include static const struct pios_spektrum_cfg pios_spektrum_cfg = { .bind = { .gpio = GPIOA, @@ -525,7 +608,6 @@ static const struct pios_spektrum_cfg pios_spektrum_cfg = { #define PIOS_COM_TELEM_RF_TX_BUF_LEN 192 #define PIOS_COM_GPS_RX_BUF_LEN 96 -#define PIOS_COM_GPS_TX_BUF_LEN 96 #define PIOS_COM_TELEM_USB_RX_BUF_LEN 192 #define PIOS_COM_TELEM_USB_TX_BUF_LEN 192 @@ -536,65 +618,106 @@ static const struct pios_spektrum_cfg pios_spektrum_cfg = { * Pios servo configuration structures */ #include -static const struct pios_servo_channel pios_servo_channels[] = { +static const struct pios_tim_channel pios_tim_servoport_all_pins[] = { { .timer = TIM4, - .port = GPIOB, - .channel = TIM_Channel_1, - .pin = GPIO_Pin_6, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_6, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, }, { .timer = TIM4, - .port = GPIOB, - .channel = TIM_Channel_2, - .pin = GPIO_Pin_7, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_7, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, }, { .timer = TIM4, - .port = GPIOB, - .channel = TIM_Channel_3, - .pin = GPIO_Pin_8, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_8, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, }, { .timer = TIM4, - .port = GPIOB, - .channel = TIM_Channel_4, - .pin = GPIO_Pin_9, + .timer_chan = TIM_Channel_4, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_9, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, }, { .timer = TIM8, - .port = GPIOC, - .channel = TIM_Channel_1, - .pin = GPIO_Pin_6, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_6, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, }, { .timer = TIM8, - .port = GPIOC, - .channel = TIM_Channel_2, - .pin = GPIO_Pin_7, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_7, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, }, { .timer = TIM8, - .port = GPIOC, - .channel = TIM_Channel_3, - .pin = GPIO_Pin_8, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_8, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, }, { .timer = TIM8, - .port = GPIOC, - .channel = TIM_Channel_4, - .pin = GPIO_Pin_9, + .timer_chan = TIM_Channel_4, + .pin = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_9, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, }, }; const struct pios_servo_cfg pios_servo_cfg = { - .tim_base_init = { - .TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1, - .TIM_ClockDivision = TIM_CKD_DIV1, - .TIM_CounterMode = TIM_CounterMode_Up, - .TIM_Period = ((1000000 / PIOS_SERVO_UPDATE_HZ) - 1), - .TIM_RepetitionCounter = 0x0000, - }, .tim_oc_init = { .TIM_OCMode = TIM_OCMode_PWM1, .TIM_OutputState = TIM_OutputState_Enable, @@ -605,13 +728,8 @@ const struct pios_servo_cfg pios_servo_cfg = { .TIM_OCIdleState = TIM_OCIdleState_Reset, .TIM_OCNIdleState = TIM_OCNIdleState_Reset, }, - .gpio_init = { - .GPIO_Mode = GPIO_Mode_AF_PP, - .GPIO_Speed = GPIO_Speed_2MHz, - }, - .remap = 0, - .channels = pios_servo_channels, - .num_channels = NELEMENTS(pios_servo_channels), + .channels = pios_tim_servoport_all_pins, + .num_channels = NELEMENTS(pios_tim_servoport_all_pins), }; @@ -620,112 +738,117 @@ const struct pios_servo_cfg pios_servo_cfg = { */ #if defined(PIOS_INCLUDE_PWM) #include -static const struct pios_pwm_channel pios_pwm_channels[] = { +static const struct pios_tim_channel pios_tim_rcvrport_all_channels[] = { { .timer = TIM1, - .port = GPIOA, - .ccr = TIM_IT_CC2, - .channel = TIM_Channel_2, - .pin = GPIO_Pin_9, - }, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_9, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, { .timer = TIM1, - .port = GPIOA, - .ccr = TIM_IT_CC3, - .channel = TIM_Channel_3, - .pin = GPIO_Pin_10, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, }, { .timer = TIM5, - .port = GPIOA, - .ccr = TIM_IT_CC1, - .channel = TIM_Channel_1, - .pin = GPIO_Pin_0 + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_0, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, }, { .timer = TIM1, - .port = GPIOA, - .ccr = TIM_IT_CC1, - .channel = TIM_Channel_1, - .pin = GPIO_Pin_8, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_8, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, }, { .timer = TIM3, - .port = GPIOB, - .ccr = TIM_IT_CC4, - .channel = TIM_Channel_4, - .pin = GPIO_Pin_1, + .timer_chan = TIM_Channel_4, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_1, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, }, { .timer = TIM3, - .port = GPIOB, - .ccr = TIM_IT_CC3, - .channel = TIM_Channel_3, - .pin = GPIO_Pin_0, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_0, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, }, { .timer = TIM3, - .port = GPIOB, - .ccr = TIM_IT_CC1, - .channel = TIM_Channel_1, - .pin = GPIO_Pin_4, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_4, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + .remap = GPIO_PartialRemap_TIM3, }, { .timer = TIM3, - .port = GPIOB, - .ccr = TIM_IT_CC2, - .channel = TIM_Channel_2, - .pin = GPIO_Pin_5, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_5, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + .remap = GPIO_PartialRemap_TIM3, }, }; -void TIM1_CC_IRQHandler(); -void TIM3_IRQHandler(); -void TIM5_IRQHandler(); -void TIM1_CC_IRQHandler() __attribute__ ((alias ("PIOS_TIM1_CC_irq_handler"))); -void TIM3_IRQHandler() __attribute__ ((alias ("PIOS_TIM3_irq_handler"))); -void TIM5_IRQHandler() __attribute__ ((alias ("PIOS_TIM5_irq_handler"))); const struct pios_pwm_cfg pios_pwm_cfg = { - .tim_base_init = { - .TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1, - .TIM_ClockDivision = TIM_CKD_DIV1, - .TIM_CounterMode = TIM_CounterMode_Up, - .TIM_Period = 0xFFFF, - .TIM_RepetitionCounter = 0x0000, - }, .tim_ic_init = { .TIM_ICPolarity = TIM_ICPolarity_Rising, .TIM_ICSelection = TIM_ICSelection_DirectTI, .TIM_ICPrescaler = TIM_ICPSC_DIV1, .TIM_ICFilter = 0x0, }, - .gpio_init = { - .GPIO_Mode = GPIO_Mode_IPD, - .GPIO_Speed = GPIO_Speed_2MHz, - }, - .remap = GPIO_PartialRemap_TIM3, - .irq = { - .init = { - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .channels = pios_pwm_channels, - .num_channels = NELEMENTS(pios_pwm_channels), + .channels = pios_tim_rcvrport_all_channels, + .num_channels = NELEMENTS(pios_tim_rcvrport_all_channels), }; -void PIOS_TIM1_CC_irq_handler() -{ - PIOS_PWM_irq_handler(TIM1); -} -void PIOS_TIM3_irq_handler() -{ - PIOS_PWM_irq_handler(TIM3); -} -void PIOS_TIM5_irq_handler() -{ - PIOS_PWM_irq_handler(TIM5); -} #endif /* @@ -733,42 +856,7 @@ void PIOS_TIM5_irq_handler() */ #if defined(PIOS_INCLUDE_PPM) #include -void TIM6_IRQHandler(); -void TIM6_IRQHandler() __attribute__ ((alias ("PIOS_TIM6_irq_handler"))); -static const struct pios_ppmsv_cfg pios_ppmsv_cfg = { - .tim_base_init = { - .TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1, /* For 1 uS accuracy */ - .TIM_ClockDivision = TIM_CKD_DIV1, - .TIM_CounterMode = TIM_CounterMode_Up, - .TIM_Period = ((1000000 / 25) - 1), /* 25 Hz */ - .TIM_RepetitionCounter = 0x0000, - }, - .irq = { - .init = { - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .timer = TIM6, - .ccr = TIM_IT_Update, -}; - -void PIOS_TIM6_irq_handler(void) -{ - PIOS_PPMSV_irq_handler(); -} - -void TIM1_CC_IRQHandler(); -void TIM1_CC_IRQHandler() __attribute__ ((alias ("PIOS_TIM1_CC_irq_handler"))); static const struct pios_ppm_cfg pios_ppm_cfg = { - .tim_base_init = { - .TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1, /* For 1 uS accuracy */ - .TIM_ClockDivision = TIM_CKD_DIV1, - .TIM_CounterMode = TIM_CounterMode_Up, - .TIM_Period = 0xFFFF, - .TIM_RepetitionCounter = 0x0000, - }, .tim_ic_init = { .TIM_ICPolarity = TIM_ICPolarity_Rising, .TIM_ICSelection = TIM_ICSelection_DirectTI, @@ -776,30 +864,11 @@ static const struct pios_ppm_cfg pios_ppm_cfg = { .TIM_ICFilter = 0x0, .TIM_Channel = TIM_Channel_2, }, - .gpio_init = { - .GPIO_Mode = GPIO_Mode_IPD, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Pin = GPIO_Pin_9, - }, - .remap = 0, - .irq = { - .init = { - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - .NVIC_IRQChannel = TIM1_CC_IRQn, - }, - }, - .timer = TIM1, - .port = GPIOA, - .ccr = TIM_IT_CC2, + /* Use only the first channel for ppm */ + .channels = &pios_tim_rcvrport_all_channels[0], + .num_channels = 1, }; -void PIOS_TIM1_CC_irq_handler(void) -{ - PIOS_PPM_irq_handler(); -} - #endif //PPM #if defined(PIOS_INCLUDE_I2C) @@ -965,8 +1034,12 @@ static const struct stm32_gpio pios_debug_pins[] = { #if defined(PIOS_INCLUDE_RCVR) #include "pios_rcvr_priv.h" -struct pios_rcvr_channel_map pios_rcvr_channel_to_id_map[PIOS_RCVR_MAX_CHANNELS]; -uint32_t pios_rcvr_max_channel; +/* 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 /* PIOS_INCLUDE_RCVR */ #if defined(PIOS_INCLUDE_USB_HID) @@ -1004,8 +1077,9 @@ void PIOS_Board_Init(void) { /* Remap AFIO pin */ //GPIO_PinRemapConfig( GPIO_Remap_SWJ_NoJTRST, ENABLE); - /* Debug services */ - PIOS_DEBUG_Init(); +#ifdef PIOS_DEBUG_ENABLE_DEBUG_PINS + PIOS_DEBUG_Init(&pios_tim_servo_all_channels, NELEMENTS(pios_tim_servo_all_channels)); +#endif /* PIOS_DEBUG_ENABLE_DEBUG_PINS */ /* Delay system */ PIOS_DELAY_Init(); @@ -1036,6 +1110,14 @@ void PIOS_Board_Init(void) { /* Initialize the task monitor library */ TaskMonitorInitialize(); + /* Set up pulse timers */ + PIOS_TIM_InitClock(&tim_1_cfg); + PIOS_TIM_InitClock(&tim_3_cfg); + PIOS_TIM_InitClock(&tim_5_cfg); + + PIOS_TIM_InitClock(&tim_4_cfg); + PIOS_TIM_InitClock(&tim_8_cfg); + /* Prepare the AHRS Comms upper layer protocol */ AhrsInitComms(); @@ -1047,129 +1129,136 @@ void PIOS_Board_Init(void) { /* Bind the AHRS comms layer to the AHRS SPI link */ AhrsConnect(pios_spi_ahrs_id); - /* Initialize the PiOS library */ -#if defined(PIOS_INCLUDE_COM) + /* Configure the main IO port */ + uint8_t hwsettings_op_mainport; + HwSettingsOP_MainPortGet(&hwsettings_op_mainport); + + switch (hwsettings_op_mainport) { + case HWSETTINGS_OP_MAINPORT_DISABLED: + break; + case HWSETTINGS_OP_MAINPORT_TELEMETRY: #if defined(PIOS_INCLUDE_TELEMETRY_RF) - { - uint32_t pios_usart_telem_rf_id; - if (PIOS_USART_Init(&pios_usart_telem_rf_id, &pios_usart_telem_cfg)) { - PIOS_Assert(0); - } + { + uint32_t pios_usart_telem_rf_id; + if (PIOS_USART_Init(&pios_usart_telem_rf_id, &pios_usart_telem_cfg)) { + PIOS_Assert(0); + } - uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_usart_com_driver, pios_usart_telem_rf_id, - rx_buffer, PIOS_COM_TELEM_RF_RX_BUF_LEN, - tx_buffer, PIOS_COM_TELEM_RF_TX_BUF_LEN)) { - PIOS_Assert(0); + uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_RX_BUF_LEN); + uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_TX_BUF_LEN); + PIOS_Assert(rx_buffer); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_usart_com_driver, pios_usart_telem_rf_id, + rx_buffer, PIOS_COM_TELEM_RF_RX_BUF_LEN, + tx_buffer, PIOS_COM_TELEM_RF_TX_BUF_LEN)) { + PIOS_Assert(0); + } } - } #endif /* PIOS_INCLUDE_TELEMETRY_RF */ - -#if defined(PIOS_INCLUDE_GPS) - { - uint32_t pios_usart_gps_id; - if (PIOS_USART_Init(&pios_usart_gps_id, &pios_usart_gps_cfg)) { - PIOS_Assert(0); - } - uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_GPS_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_GPS_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_gps_id, - rx_buffer, PIOS_COM_GPS_RX_BUF_LEN, - tx_buffer, PIOS_COM_GPS_TX_BUF_LEN)) { - PIOS_Assert(0); - } + break; } -#endif /* PIOS_INCLUDE_GPS */ -#endif - PIOS_Servo_Init(); + /* Configure the flexi port */ + uint8_t hwsettings_op_flexiport; + HwSettingsOP_FlexiPortGet(&hwsettings_op_flexiport); + + switch (hwsettings_op_flexiport) { + case HWSETTINGS_OP_FLEXIPORT_DISABLED: + break; + case HWSETTINGS_OP_FLEXIPORT_GPS: +#if defined(PIOS_INCLUDE_GPS) + { + uint32_t pios_usart_gps_id; + if (PIOS_USART_Init(&pios_usart_gps_id, &pios_usart_gps_cfg)) { + PIOS_Assert(0); + } + uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_GPS_RX_BUF_LEN); + PIOS_Assert(rx_buffer); + if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_gps_id, + rx_buffer, PIOS_COM_GPS_RX_BUF_LEN, + NULL, 0)) { + PIOS_Assert(0); + } + } +#endif /* PIOS_INCLUDE_GPS */ + break; + } + +#ifndef PIOS_DEBUG_ENABLE_DEBUG_PINS + PIOS_Servo_Init(&pios_servo_cfg); +#endif /* PIOS_DEBUG_ENABLE_DEBUG_PINS */ + PIOS_ADC_Init(); PIOS_GPIO_Init(); - /* Configure the selected receiver */ - uint8_t manualcontrolsettings_inputmode; - ManualControlSettingsInitialize(); - ManualControlSettingsInputModeGet(&manualcontrolsettings_inputmode); + /* Configure the aux port */ + uint8_t hwsettings_op_auxport; + HwSettingsOP_AuxPortGet(&hwsettings_op_auxport); - switch (manualcontrolsettings_inputmode) { - case MANUALCONTROLSETTINGS_INPUTMODE_PWM: -#if defined(PIOS_INCLUDE_PWM) -#if (PIOS_PWM_NUM_INPUTS > PIOS_RCVR_MAX_CHANNELS) -#error More receiver inputs than available devices -#endif - PIOS_PWM_Init(); - uint32_t pios_pwm_rcvr_id; - if (PIOS_RCVR_Init(&pios_pwm_rcvr_id, &pios_pwm_rcvr_driver, 0)) { - PIOS_Assert(0); - } - for (uint8_t i = 0; - i < PIOS_PWM_NUM_INPUTS && pios_rcvr_max_channel < NELEMENTS(pios_rcvr_channel_to_id_map); - i++) { - pios_rcvr_channel_to_id_map[pios_rcvr_max_channel].id = pios_pwm_rcvr_id; - pios_rcvr_channel_to_id_map[pios_rcvr_max_channel].channel = i; - pios_rcvr_max_channel++; - } -#endif /* PIOS_INCLUDE_PWM */ - break; - case MANUALCONTROLSETTINGS_INPUTMODE_PPM: -#if defined(PIOS_INCLUDE_PPM) -#if (PIOS_PPM_NUM_INPUTS > PIOS_RCVR_MAX_CHANNELS) -#error More receiver inputs than available devices -#endif - PIOS_PPM_Init(); - uint32_t pios_ppm_rcvr_id; - if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, 0)) { - PIOS_Assert(0); - } - for (uint8_t i = 0; - i < PIOS_PPM_NUM_INPUTS && pios_rcvr_max_channel < NELEMENTS(pios_rcvr_channel_to_id_map); - i++) { - pios_rcvr_channel_to_id_map[pios_rcvr_max_channel].id = pios_ppm_rcvr_id; - pios_rcvr_channel_to_id_map[pios_rcvr_max_channel].channel = i; - pios_rcvr_max_channel++; - } -#endif /* PIOS_INCLUDE_PPM */ - break; - case MANUALCONTROLSETTINGS_INPUTMODE_SPEKTRUM: + switch (hwsettings_op_auxport) { + case HWSETTINGS_OP_AUXPORT_DISABLED: + break; + case HWSETTINGS_OP_AUXPORT_DEBUG: + /* Not supported yet */ + break; + case HWSETTINGS_OP_AUXPORT_SPEKTRUM1: #if defined(PIOS_INCLUDE_SPEKTRUM) -#if (PIOS_SPEKTRUM_NUM_INPUTS > PIOS_RCVR_MAX_CHANNELS) -#error More receiver inputs than available devices -#endif - { - uint32_t pios_usart_spektrum_id; - if (PIOS_USART_Init(&pios_usart_spektrum_id, &pios_usart_spektrum_cfg)) { - PIOS_Assert(0); - } - - uint32_t pios_spektrum_id; - if (PIOS_SPEKTRUM_Init(&pios_spektrum_id, &pios_spektrum_cfg, &pios_usart_com_driver, pios_usart_spektrum_id, false)) { - PIOS_Assert(0); - } - - uint32_t pios_spektrum_rcvr_id; - if (PIOS_RCVR_Init(&pios_spektrum_rcvr_id, &pios_spektrum_rcvr_driver, 0)) { - PIOS_Assert(0); - } - for (uint8_t i = 0; - i < PIOS_SPEKTRUM_NUM_INPUTS && pios_rcvr_max_channel < NELEMENTS(pios_rcvr_channel_to_id_map); - i++) { - pios_rcvr_channel_to_id_map[pios_rcvr_max_channel].id = pios_spektrum_rcvr_id; - pios_rcvr_channel_to_id_map[pios_rcvr_max_channel].channel = i; - pios_rcvr_max_channel++; - } + { + uint32_t pios_usart_spektrum_id; + if (PIOS_USART_Init(&pios_usart_spektrum_id, &pios_usart_spektrum_cfg)) { + PIOS_Assert(0); } + + uint32_t pios_spektrum_id; + if (PIOS_SPEKTRUM_Init(&pios_spektrum_id, &pios_spektrum_cfg, &pios_usart_com_driver, pios_usart_spektrum_id, false)) { + PIOS_Assert(0); + } + + uint32_t pios_spektrum_rcvr_id; + if (PIOS_RCVR_Init(&pios_spektrum_rcvr_id, &pios_spektrum_rcvr_driver, pios_spektrum_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SPEKTRUM1] = pios_spektrum_rcvr_id; + } #endif - break; - case MANUALCONTROLSETTINGS_INPUTMODE_SBUS: -#if defined(PIOS_INCLUDE_SBUS) -#error SBUS NOT ON OP YET -#endif /* PIOS_INCLUDE_SBUS */ - break; + break; + } + + /* Configure the rcvr port */ + uint8_t hwsettings_rcvrport; + HwSettingsRcvrPortGet(&hwsettings_rcvrport); + + switch (hwsettings_rcvrport) { + case HWSETTINGS_RCVRPORT_DISABLED: + break; + case HWSETTINGS_RCVRPORT_PWM: +#if defined(PIOS_INCLUDE_PWM) + { + uint32_t pios_pwm_id; + PIOS_PWM_Init(&pios_pwm_id, &pios_pwm_cfg); + + uint32_t pios_pwm_rcvr_id; + if (PIOS_RCVR_Init(&pios_pwm_rcvr_id, &pios_pwm_rcvr_driver, pios_pwm_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PWM] = pios_pwm_rcvr_id; + } +#endif /* PIOS_INCLUDE_PWM */ + break; + case HWSETTINGS_RCVRPORT_PPM: +#if defined(PIOS_INCLUDE_PPM) + { + uint32_t pios_ppm_id; + PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_cfg); + + uint32_t pios_ppm_rcvr_id; + if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM] = pios_ppm_rcvr_id; + } +#endif /* PIOS_INCLUDE_PPM */ + break; } #if defined(PIOS_INCLUDE_USB_HID) diff --git a/flight/OpenPilot/System/pios_board_posix.c b/flight/OpenPilot/System/pios_board_posix.c index e1e8dcc54..37fadd760 100644 --- a/flight/OpenPilot/System/pios_board_posix.c +++ b/flight/OpenPilot/System/pios_board_posix.c @@ -71,7 +71,7 @@ const struct pios_udp_cfg pios_udp_aux_cfg = { #define PIOS_COM_TELEM_RF_RX_BUF_LEN 192 #define PIOS_COM_TELEM_RF_TX_BUF_LEN 192 -#define PIOS_COM_GPS_RX_BUF_LEN 192 +#define PIOS_COM_GPS_RX_BUF_LEN 96 /* * Board specific number of devices. @@ -164,12 +164,10 @@ void PIOS_Board_Init(void) { PIOS_Assert(0); } uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_GPS_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_GPS_RX_BUF_LEN); PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); if (PIOS_COM_Init(&pios_com_gps_id, &pios_udp_com_driver, pios_udp_gps_id, rx_buffer, PIOS_COM_GPS_RX_BUF_LEN, - tx_buffer, PIOS_COM_GPS_RX_BUF_LEN)) { + NULL, 0)) { PIOS_Assert(0); } } diff --git a/flight/OpenPilot/UAVObjects.inc b/flight/OpenPilot/UAVObjects.inc index f142a9336..cbe2f79b0 100644 --- a/flight/OpenPilot/UAVObjects.inc +++ b/flight/OpenPilot/UAVObjects.inc @@ -68,6 +68,8 @@ UAVOBJSRCFILENAMES += velocityactual UAVOBJSRCFILENAMES += velocitydesired UAVOBJSRCFILENAMES += watchdogstatus UAVOBJSRCFILENAMES += flightstatus +UAVOBJSRCFILENAMES += hwsettings +UAVOBJSRCFILENAMES += receiveractivity UAVOBJSRCFILENAMES += cameradesired UAVOBJSRCFILENAMES += camerastabsettings diff --git a/flight/PiOS.win32/inc/pios_initcall.h b/flight/PiOS.win32/inc/pios_initcall.h index edd9ddc08..bdb47cc8e 100644 --- a/flight/PiOS.win32/inc/pios_initcall.h +++ b/flight/PiOS.win32/inc/pios_initcall.h @@ -38,7 +38,7 @@ * and we cannot define a linker script for each of them atm */ -#define MODULE_INITCALL(ifn, iparam, sfn, sparam, flags) +#define MODULE_INITCALL(ifn, sfn) #define MODULE_TASKCREATE_ALL diff --git a/flight/PiOS/Boards/STM32103CB_CC_Rev1.h b/flight/PiOS/Boards/STM32103CB_CC_Rev1.h index 18e0da624..42b3a5e4d 100644 --- a/flight/PiOS/Boards/STM32103CB_CC_Rev1.h +++ b/flight/PiOS/Boards/STM32103CB_CC_Rev1.h @@ -206,22 +206,25 @@ extern uint32_t pios_com_telem_usb_id; // PIOS_RCVR // See also pios_board.c //------------------------ -#define PIOS_RCVR_MAX_DEVS 1 +#define PIOS_RCVR_MAX_DEVS 3 #define PIOS_RCVR_MAX_CHANNELS 12 //------------------------- // Receiver PPM input //------------------------- +#define PIOS_PPM_MAX_DEVS 1 #define PIOS_PPM_NUM_INPUTS 12 //------------------------- // Receiver PWM input //------------------------- +#define PIOS_PWM_MAX_DEVS 1 #define PIOS_PWM_NUM_INPUTS 6 //------------------------- // Receiver SPEKTRUM input //------------------------- +#define PIOS_SPEKTRUM_MAX_DEVS 2 #define PIOS_SPEKTRUM_NUM_INPUTS 12 //------------------------- @@ -230,6 +233,11 @@ extern uint32_t pios_com_telem_usb_id; #define PIOS_SERVO_UPDATE_HZ 50 #define PIOS_SERVOS_INITIAL_POSITION 0 /* dont want to start motors, have no pulse till settings loaded */ +//-------------------------- +// Timer controller settings +//-------------------------- +#define PIOS_TIM_MAX_DEVS 3 + //------------------------- // GPIO //------------------------- diff --git a/flight/PiOS/Boards/STM3210E_OP.h b/flight/PiOS/Boards/STM3210E_OP.h index 3098ee259..ea925a271 100644 --- a/flight/PiOS/Boards/STM3210E_OP.h +++ b/flight/PiOS/Boards/STM3210E_OP.h @@ -185,16 +185,19 @@ extern uint32_t pios_com_aux_id; //------------------------- // Receiver PPM input //------------------------- +#define PIOS_PPM_MAX_DEVS 1 #define PIOS_PPM_NUM_INPUTS 12 //------------------------- // Receiver PWM input //------------------------- +#define PIOS_PWM_MAX_DEVS 1 #define PIOS_PWM_NUM_INPUTS 8 //------------------------- // Receiver SPEKTRUM input //------------------------- +#define PIOS_SPEKTRUM_MAX_DEVS 1 #define PIOS_SPEKTRUM_NUM_INPUTS 12 //------------------------- @@ -203,6 +206,11 @@ extern uint32_t pios_com_aux_id; #define PIOS_SERVO_UPDATE_HZ 50 #define PIOS_SERVOS_INITIAL_POSITION 0 /* dont want to start motors, have no pulse till settings loaded */ +//-------------------------- +// Timer controller settings +//-------------------------- +#define PIOS_TIM_MAX_DEVS 3 + //------------------------- // ADC // PIOS_ADC_PinGet(0) = Temperature Sensor (On-board) diff --git a/flight/PiOS/Common/pios_com.c b/flight/PiOS/Common/pios_com.c index b7a9a67e5..e7fba8867 100644 --- a/flight/PiOS/Common/pios_com.c +++ b/flight/PiOS/Common/pios_com.c @@ -67,12 +67,12 @@ static bool PIOS_COM_validate(struct pios_com_dev * com_dev) return (com_dev && (com_dev->magic == PIOS_COM_DEV_MAGIC)); } -#if defined(PIOS_INCLUDE_FREERTOS) && 0 +#if defined(PIOS_INCLUDE_FREERTOS) static struct pios_com_dev * PIOS_COM_alloc(void) { struct pios_com_dev * com_dev; - com_dev = (struct pios_com_dev *)malloc(sizeof(*com_dev)); + com_dev = (struct pios_com_dev *)pvPortMalloc(sizeof(*com_dev)); if (!com_dev) return (NULL); com_dev->magic = PIOS_COM_DEV_MAGIC; diff --git a/flight/PiOS/Common/pios_gcsrcvr.c b/flight/PiOS/Common/pios_gcsrcvr.c new file mode 100644 index 000000000..18e6644a6 --- /dev/null +++ b/flight/PiOS/Common/pios_gcsrcvr.c @@ -0,0 +1,75 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_GCSRCVR GCS Receiver Input Functions + * @brief Code to read the channels within the GCS Receiver UAVObject + * @{ + * + * @file pios_gcsrcvr.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief GCS Input functions (STM32 dependent) + * @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 + */ + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_GCSRCVR) + +#include "pios_gcsrcvr_priv.h" + +static GCSReceiverData gcsreceiverdata; + +/* Provide a RCVR driver */ +static int32_t PIOS_GCSRCVR_Get(uint32_t rcvr_id, uint8_t channel); + +const struct pios_rcvr_driver pios_gcsrcvr_rcvr_driver = { + .read = PIOS_GCSRCVR_Get, +}; + +static void gcsreceiver_updated(UAVObjEvent * ev) +{ + if (ev->obj == GCSReceiverHandle()) { + GCSReceiverGet(&gcsreceiverdata); + } +} + +void PIOS_GCSRCVR_Init(void) +{ + /* Register uavobj callback */ + GCSReceiverConnectCallback (gcsreceiver_updated); +} + +static int32_t PIOS_GCSRCVR_Get(uint32_t rcvr_id, uint8_t channel) +{ + if (channel >= GCSRECEIVER_CHANNEL_NUMELEM) { + /* channel is out of range */ + return -1; + } + + return (gcsreceiverdata.Channel[channel]); +} + +#endif /* PIOS_INCLUDE_GCSRCVR */ + +/** + * @} + * @} + */ diff --git a/flight/PiOS/Common/pios_rcvr.c b/flight/PiOS/Common/pios_rcvr.c index 29acb2594..02778bad4 100644 --- a/flight/PiOS/Common/pios_rcvr.c +++ b/flight/PiOS/Common/pios_rcvr.c @@ -20,12 +20,12 @@ static bool PIOS_RCVR_validate(struct pios_rcvr_dev * rcvr_dev) return (rcvr_dev->magic == PIOS_RCVR_DEV_MAGIC); } -#if defined(PIOS_INCLUDE_FREERTOS) && 0 +#if defined(PIOS_INCLUDE_FREERTOS) static struct pios_rcvr_dev * PIOS_RCVR_alloc(void) { struct pios_rcvr_dev * rcvr_dev; - rcvr_dev = (struct pios_rcvr_dev *)malloc(sizeof(*rcvr_dev)); + rcvr_dev = (struct pios_rcvr_dev *)pvPortMalloc(sizeof(*rcvr_dev)); if (!rcvr_dev) return (NULL); rcvr_dev->magic = PIOS_RCVR_DEV_MAGIC; @@ -76,8 +76,20 @@ out_fail: return(-1); } +/** + * @brief Reads an input channel from the appropriate driver + * @param[in] rcvr_id driver to read from + * @param[in] channel channel to read + * @returns Unitless input value + * @retval PIOS_RCVR_TIMEOUT indicates a failsafe or timeout from that channel + * @retval PIOS_RCVR_INVALID invalid channel for this driver (usually out of range supported) + * @retval PIOS_RCVR_NODRIVER driver was not initialized + */ int32_t PIOS_RCVR_Read(uint32_t rcvr_id, uint8_t channel) { + if (rcvr_id == 0) + return PIOS_RCVR_NODRIVER; + struct pios_rcvr_dev * rcvr_dev = (struct pios_rcvr_dev *)rcvr_id; if (!PIOS_RCVR_validate(rcvr_dev)) { diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_tim.h b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_tim.h index 6529c0b0a..388d276e4 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_tim.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_tim.h @@ -1025,12 +1025,12 @@ typedef struct */ void TIM_DeInit(TIM_TypeDef* TIMx); -void TIM_TimeBaseInit(TIM_TypeDef* TIMx, TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct); -void TIM_OC1Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct); -void TIM_OC2Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct); -void TIM_OC3Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct); -void TIM_OC4Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct); -void TIM_ICInit(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct); +void TIM_TimeBaseInit(TIM_TypeDef* TIMx, const TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct); +void TIM_OC1Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_OC2Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_OC3Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_OC4Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_ICInit(TIM_TypeDef* TIMx, const TIM_ICInitTypeDef* TIM_ICInitStruct); void TIM_PWMIConfig(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct); void TIM_BDTRConfig(TIM_TypeDef* TIMx, TIM_BDTRInitTypeDef *TIM_BDTRInitStruct); void TIM_TimeBaseStructInit(TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct); diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_tim.c b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_tim.c index 780105589..2f31c9a1a 100755 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_tim.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_tim.c @@ -221,7 +221,7 @@ void TIM_DeInit(TIM_TypeDef* TIMx) * structure that contains the configuration information for the specified TIM peripheral. * @retval None */ -void TIM_TimeBaseInit(TIM_TypeDef* TIMx, TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct) +void TIM_TimeBaseInit(TIM_TypeDef* TIMx, const TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct) { uint16_t tmpcr1 = 0; @@ -274,7 +274,7 @@ void TIM_TimeBaseInit(TIM_TypeDef* TIMx, TIM_TimeBaseInitTypeDef* TIM_TimeBaseIn * that contains the configuration information for the specified TIM peripheral. * @retval None */ -void TIM_OC1Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct) +void TIM_OC1Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct) { uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; @@ -357,7 +357,7 @@ void TIM_OC1Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct) * that contains the configuration information for the specified TIM peripheral. * @retval None */ -void TIM_OC2Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct) +void TIM_OC2Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct) { uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; @@ -439,7 +439,7 @@ void TIM_OC2Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct) * that contains the configuration information for the specified TIM peripheral. * @retval None */ -void TIM_OC3Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct) +void TIM_OC3Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct) { uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; @@ -518,7 +518,7 @@ void TIM_OC3Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct) * that contains the configuration information for the specified TIM peripheral. * @retval None */ -void TIM_OC4Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct) +void TIM_OC4Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct) { uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; @@ -582,7 +582,7 @@ void TIM_OC4Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct) * that contains the configuration information for the specified TIM peripheral. * @retval None */ -void TIM_ICInit(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct) +void TIM_ICInit(TIM_TypeDef* TIMx, const TIM_ICInitTypeDef* TIM_ICInitStruct) { /* Check the parameters */ assert_param(IS_TIM_CHANNEL(TIM_ICInitStruct->TIM_Channel)); diff --git a/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_sections.ld b/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_sections.ld index 57530d320..568dddffa 100644 --- a/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_sections.ld +++ b/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_sections.ld @@ -1,5 +1,5 @@ /* This is the size of the stack for all FreeRTOS IRQs */ -_irq_stack_size = 0x180; +_irq_stack_size = 0x1A0; /* This is the size of the stack for early init: life span is until scheduler starts */ _init_stack_size = 0x100; diff --git a/flight/PiOS/STM32F10x/pios_debug.c b/flight/PiOS/STM32F10x/pios_debug.c index ca4f67dc5..18ea0071b 100644 --- a/flight/PiOS/STM32F10x/pios_debug.c +++ b/flight/PiOS/STM32F10x/pios_debug.c @@ -34,39 +34,41 @@ // Global variables const char *PIOS_DEBUG_AssertMsg = "ASSERT FAILED"; -#include -extern const struct pios_servo_channel pios_servo_channels[]; -#define PIOS_SERVO_GPIO_PORT_1TO4 pios_servo_channels[0].port -#define PIOS_SERVO_GPIO_PORT_5TO8 pios_servo_channels[4].port -#define PIOS_SERVO_GPIO_PIN_1 pios_servo_channels[0].pin -#define PIOS_SERVO_GPIO_PIN_2 pios_servo_channels[1].pin -#define PIOS_SERVO_GPIO_PIN_3 pios_servo_channels[2].pin -#define PIOS_SERVO_GPIO_PIN_4 pios_servo_channels[3].pin -#define PIOS_SERVO_GPIO_PIN_5 pios_servo_channels[4].pin -#define PIOS_SERVO_GPIO_PIN_6 pios_servo_channels[5].pin -#define PIOS_SERVO_GPIO_PIN_7 pios_servo_channels[6].pin -#define PIOS_SERVO_GPIO_PIN_8 pios_servo_channels[7].pin -/* Private Function Prototypes */ +#ifdef PIOS_ENABLE_DEBUG_PINS +static const struct pios_tim_channel * debug_channels; +static uint8_t debug_num_channels; +#endif /* PIOS_ENABLE_DEBUG_PINS */ /** * Initialise Debug-features */ -void PIOS_DEBUG_Init(void) +void PIOS_DEBUG_Init(const struct pios_tim_channel * channels, uint8_t num_channels) { #ifdef PIOS_ENABLE_DEBUG_PINS - // Initialise Servo pins as standard output pins - GPIO_InitTypeDef GPIO_InitStructure; - GPIO_StructInit(&GPIO_InitStructure); - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; - GPIO_InitStructure.GPIO_Pin = PIOS_SERVO_GPIO_PIN_1 | PIOS_SERVO_GPIO_PIN_2 | PIOS_SERVO_GPIO_PIN_3 | PIOS_SERVO_GPIO_PIN_4; - GPIO_Init(PIOS_SERVO_GPIO_PORT_1TO4, &GPIO_InitStructure); - GPIO_InitStructure.GPIO_Pin = PIOS_SERVO_GPIO_PIN_5 | PIOS_SERVO_GPIO_PIN_6 | PIOS_SERVO_GPIO_PIN_7 | PIOS_SERVO_GPIO_PIN_8; - GPIO_Init(PIOS_SERVO_GPIO_PORT_5TO8, &GPIO_InitStructure); + PIOS_Assert(channels); + PIOS_Assert(num_channels); - // Drive all pins low - PIOS_SERVO_GPIO_PORT_1TO4->BRR = PIOS_SERVO_GPIO_PIN_1 | PIOS_SERVO_GPIO_PIN_2 | PIOS_SERVO_GPIO_PIN_3 | PIOS_SERVO_GPIO_PIN_4; - PIOS_SERVO_GPIO_PORT_5TO8->BRR = PIOS_SERVO_GPIO_PIN_5 | PIOS_SERVO_GPIO_PIN_6 | PIOS_SERVO_GPIO_PIN_7 | PIOS_SERVO_GPIO_PIN_8; + /* Store away the GPIOs we've been given */ + debug_channels = channels; + debug_num_channels = num_channels; + + /* Configure the GPIOs we've been given */ + for (uint8_t i = 0; i < num_channels; i++) { + const struct pios_tim_channel * chan = &channels[i]; + + // Initialise pins as standard output pins + GPIO_InitTypeDef GPIO_InitStructure; + GPIO_StructInit(&GPIO_InitStructure); + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; + GPIO_InitStructure.GPIO_Pin = chan->init->GPIO_Pin; + + /* Initialize the GPIO */ + GPIO_Init(chan->init->port, &GPIO_InitStructure); + + /* Set the pin low */ + GPIO_WriteBit(chan->init->port, chan->init->GPIO_Pin, Bit_RESET); + } #endif // PIOS_ENABLE_DEBUG_PINS } @@ -74,14 +76,17 @@ void PIOS_DEBUG_Init(void) * Set debug-pin high * \param pin 0 for S1 output */ -void PIOS_DEBUG_PinHigh(uint8_t Pin) +void PIOS_DEBUG_PinHigh(uint8_t pin) { #ifdef PIOS_ENABLE_DEBUG_PINS - if (Pin < 4) { - PIOS_SERVO_GPIO_PORT_1TO4->BSRR = (PIOS_SERVO_GPIO_PIN_1 << Pin); - } else if (Pin <= 7) { - PIOS_SERVO_GPIO_PORT_5TO8->BSRR = (PIOS_SERVO_GPIO_PIN_5 << (Pin - 4)); + if (!debug_channels || pin >= debug_num_channels) { + return; } + + const struct pios_tim_channel * chan = &debug_channels[pin]; + + GPIO_WriteBit(chan->init->port, chan->init->GPIO_Pin, Bit_Set); + #endif // PIOS_ENABLE_DEBUG_PINS } @@ -89,14 +94,17 @@ void PIOS_DEBUG_PinHigh(uint8_t Pin) * Set debug-pin low * \param pin 0 for S1 output */ -void PIOS_DEBUG_PinLow(uint8_t Pin) +void PIOS_DEBUG_PinLow(uint8_t pin) { #ifdef PIOS_ENABLE_DEBUG_PINS - if (Pin < 4) { - PIOS_SERVO_GPIO_PORT_1TO4->BRR = (PIOS_SERVO_GPIO_PIN_1 << Pin); - } else if (Pin <= 7) { - PIOS_SERVO_GPIO_PORT_5TO8->BRR = (PIOS_SERVO_GPIO_PIN_5 << (Pin - 4)); + if (!debug_channels || pin >= debug_num_channels) { + return; } + + const struct pios_tim_channel * chan = &debug_channels[pin]; + + GPIO_WriteBit(chan->init->port, chan->init->GPIO_Pin, Bit_RESET); + #endif // PIOS_ENABLE_DEBUG_PINS } @@ -104,11 +112,22 @@ void PIOS_DEBUG_PinLow(uint8_t Pin) void PIOS_DEBUG_PinValue8Bit(uint8_t value) { #ifdef PIOS_ENABLE_DEBUG_PINS + if (!debug_channels) { + return; + } + uint32_t bsrr_l = ( ((~value)&0x0F)<<(16+6) ) | ((value & 0x0F)<<6); uint32_t bsrr_h = ( ((~value)&0xF0)<<(16+6-4) ) | ((value & 0xF0)<<(6-4)); + PIOS_IRQ_Disable(); - PIOS_SERVO_GPIO_PORT_1TO4->BSRR = bsrr_l; - PIOS_SERVO_GPIO_PORT_5TO8->BSRR = bsrr_h; + + /* + * This is sketchy since it assumes a particular ordering + * and bitwise layout of the channels provided to the debug code. + */ + debug_channels[0].init.port->BSRR = bsrr_l; + debug_channels[4].init.port->BSRR = bsrr_h; + PIOS_IRQ_Enable(); #endif // PIOS_ENABLE_DEBUG_PINS } @@ -116,8 +135,16 @@ void PIOS_DEBUG_PinValue8Bit(uint8_t value) void PIOS_DEBUG_PinValue4BitL(uint8_t value) { #ifdef PIOS_ENABLE_DEBUG_PINS + if (!debug_channels) { + return; + } + + /* + * This is sketchy since it assumes a particular ordering + * and bitwise layout of the channels provided to the debug code. + */ uint32_t bsrr_l = ((~(value & 0x0F)<<(16+6))) | ((value & 0x0F)<<6); - PIOS_SERVO_GPIO_PORT_1TO4->BSRR = bsrr_l; + debug_channels[0].init.port->BSRR = bsrr_l; #endif // PIOS_ENABLE_DEBUG_PINS } diff --git a/flight/PiOS/STM32F10x/pios_i2c.c b/flight/PiOS/STM32F10x/pios_i2c.c index 6734015f6..7cc50b307 100644 --- a/flight/PiOS/STM32F10x/pios_i2c.c +++ b/flight/PiOS/STM32F10x/pios_i2c.c @@ -823,12 +823,12 @@ static bool PIOS_I2C_validate(struct pios_i2c_adapter * i2c_adapter) return (i2c_adapter->magic == PIOS_I2C_DEV_MAGIC); } -#if defined(PIOS_INCLUDE_FREERTOS) && 0 -static struct pios_i2c_dev * PIOS_I2C_alloc(void) +#if defined(PIOS_INCLUDE_FREERTOS) +static struct pios_i2c_adapter * PIOS_I2C_alloc(void) { - struct pios_i2c_dev * i2c_adapter; + struct pios_i2c_adapter * i2c_adapter; - i2c_adapter = (struct pios_i2c_adapter *)malloc(sizeof(*i2c_adapter)); + i2c_adapter = (struct pios_i2c_adapter *)pvPortMalloc(sizeof(*i2c_adapter)); if (!i2c_adapter) return(NULL); i2c_adapter->magic = PIOS_I2C_DEV_MAGIC; diff --git a/flight/PiOS/STM32F10x/pios_ppm.c b/flight/PiOS/STM32F10x/pios_ppm.c index fe7421a17..aea1016d3 100644 --- a/flight/PiOS/STM32F10x/pios_ppm.c +++ b/flight/PiOS/STM32F10x/pios_ppm.c @@ -47,108 +47,139 @@ const struct pios_rcvr_driver pios_ppm_rcvr_driver = { #define PIOS_PPM_IN_MIN_SYNC_PULSE_US 3800 // microseconds #define PIOS_PPM_IN_MIN_CHANNEL_PULSE_US 750 // microseconds #define PIOS_PPM_IN_MAX_CHANNEL_PULSE_US 2250 // microseconds -#define PIOS_PPM_INPUT_INVALID 0 /* Local Variables */ static TIM_ICInitTypeDef TIM_ICInitStructure; -static uint8_t PulseIndex; -static uint32_t PreviousTime; -static uint32_t CurrentTime; -static uint32_t DeltaTime; -static uint32_t CaptureValue[PIOS_PPM_IN_MAX_NUM_CHANNELS]; -static uint32_t CaptureValueNewFrame[PIOS_PPM_IN_MAX_NUM_CHANNELS]; -static uint32_t LargeCounter; -static int8_t NumChannels; -static int8_t NumChannelsPrevFrame; -static uint8_t NumChannelCounter; - -static uint8_t supv_timer = 0; -static bool Tracking; -static bool Fresh; static void PIOS_PPM_Supervisor(uint32_t ppm_id); -void PIOS_PPM_Init(void) +enum pios_ppm_dev_magic { + PIOS_PPM_DEV_MAGIC = 0xee014d8b, +}; + +struct pios_ppm_dev { + enum pios_ppm_dev_magic magic; + const struct pios_ppm_cfg * cfg; + + uint8_t PulseIndex; + uint32_t PreviousTime; + uint32_t CurrentTime; + uint32_t DeltaTime; + uint32_t CaptureValue[PIOS_PPM_IN_MAX_NUM_CHANNELS]; + uint32_t CaptureValueNewFrame[PIOS_PPM_IN_MAX_NUM_CHANNELS]; + uint32_t LargeCounter; + int8_t NumChannels; + int8_t NumChannelsPrevFrame; + uint8_t NumChannelCounter; + + uint8_t supv_timer; + bool Tracking; + bool Fresh; +}; + +static bool PIOS_PPM_validate(struct pios_ppm_dev * ppm_dev) { - /* Flush counter variables */ - int32_t i; + return (ppm_dev->magic == PIOS_PPM_DEV_MAGIC); +} - PulseIndex = 0; - PreviousTime = 0; - CurrentTime = 0; - DeltaTime = 0; - LargeCounter = 0; - NumChannels = -1; - NumChannelsPrevFrame = -1; - NumChannelCounter = 0; - Tracking = FALSE; - Fresh = FALSE; +#if defined(PIOS_INCLUDE_FREERTOS) +static struct pios_ppm_dev * PIOS_PPM_alloc(void) +{ + struct pios_ppm_dev * ppm_dev; - for (i = 0; i < PIOS_PPM_IN_MAX_NUM_CHANNELS; i++) { - CaptureValue[i] = 0; - CaptureValueNewFrame[i] = 0; + ppm_dev = (struct pios_ppm_dev *)pvPortMalloc(sizeof(*ppm_dev)); + if (!ppm_dev) return(NULL); + + ppm_dev->magic = PIOS_PPM_DEV_MAGIC; + return(ppm_dev); +} +#else +static struct pios_ppm_dev pios_ppm_devs[PIOS_PPM_MAX_DEVS]; +static uint8_t pios_ppm_num_devs; +static struct pios_ppm_dev * PIOS_PPM_alloc(void) +{ + struct pios_ppm_dev * ppm_dev; + + if (pios_ppm_num_devs >= PIOS_PPM_MAX_DEVS) { + return (NULL); } - NVIC_InitTypeDef NVIC_InitStructure = pios_ppm_cfg.irq.init; + ppm_dev = &pios_ppm_devs[pios_ppm_num_devs++]; + ppm_dev->magic = PIOS_PPM_DEV_MAGIC; - /* Enable appropriate clock to timer module */ - switch((int32_t) pios_ppm_cfg.timer) { - case (int32_t)TIM1: - NVIC_InitStructure.NVIC_IRQChannel = TIM1_CC_IRQn; - RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1, ENABLE); - break; - case (int32_t)TIM2: - NVIC_InitStructure.NVIC_IRQChannel = TIM2_IRQn; - RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE); - break; - case (int32_t)TIM3: - NVIC_InitStructure.NVIC_IRQChannel = TIM3_IRQn; - RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE); - break; - case (int32_t)TIM4: - NVIC_InitStructure.NVIC_IRQChannel = TIM4_IRQn; - RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM4, ENABLE); - break; -#ifdef STM32F10X_HD - case (int32_t)TIM5: - NVIC_InitStructure.NVIC_IRQChannel = TIM5_IRQn; - RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM5, ENABLE); - break; - case (int32_t)TIM6: - NVIC_InitStructure.NVIC_IRQChannel = TIM6_IRQn; - RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM6, ENABLE); - break; - case (int32_t)TIM7: - NVIC_InitStructure.NVIC_IRQChannel = TIM7_IRQn; - RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM7, ENABLE); - break; - case (int32_t)TIM8: - NVIC_InitStructure.NVIC_IRQChannel = TIM8_CC_IRQn; - RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM8, ENABLE); - break; + return (ppm_dev); +} #endif + +static void PIOS_PPM_tim_overflow_cb (uint32_t id, uint32_t context, uint8_t channel, uint16_t count); +static void PIOS_PPM_tim_edge_cb (uint32_t id, uint32_t context, uint8_t channel, uint16_t count); +const static struct pios_tim_callbacks tim_callbacks = { + .overflow = PIOS_PPM_tim_overflow_cb, + .edge = PIOS_PPM_tim_edge_cb, +}; + +extern int32_t PIOS_PPM_Init(uint32_t * ppm_id, const struct pios_ppm_cfg * cfg) +{ + PIOS_DEBUG_Assert(ppm_id); + PIOS_DEBUG_Assert(cfg); + + struct pios_ppm_dev * ppm_dev; + + ppm_dev = (struct pios_ppm_dev *) PIOS_PPM_alloc(); + if (!ppm_dev) goto out_fail; + + /* Bind the configuration to the device instance */ + ppm_dev->cfg = cfg; + + /* Set up the state variables */ + ppm_dev->PulseIndex = 0; + ppm_dev->PreviousTime = 0; + ppm_dev->CurrentTime = 0; + ppm_dev->DeltaTime = 0; + ppm_dev->LargeCounter = 0; + ppm_dev->NumChannels = -1; + ppm_dev->NumChannelsPrevFrame = -1; + ppm_dev->NumChannelCounter = 0; + ppm_dev->Tracking = FALSE; + ppm_dev->Fresh = FALSE; + + for (uint8_t i = 0; i < PIOS_PPM_IN_MAX_NUM_CHANNELS; i++) { + /* Flush counter variables */ + ppm_dev->CaptureValue[i] = 0; + ppm_dev->CaptureValueNewFrame[i] = 0; + } - /* Enable timer interrupts */ - NVIC_Init(&NVIC_InitStructure); - /* Configure input pins */ - GPIO_InitTypeDef GPIO_InitStructure = pios_ppm_cfg.gpio_init; - GPIO_Init(pios_ppm_cfg.port, &GPIO_InitStructure); + uint32_t tim_id; + if (PIOS_TIM_InitChannels(&tim_id, cfg->channels, cfg->num_channels, &tim_callbacks, (uint32_t)ppm_dev)) { + return -1; + } - /* Configure timer for input capture */ - TIM_ICInitStructure = pios_ppm_cfg.tim_ic_init; - TIM_ICInit(pios_ppm_cfg.timer, &TIM_ICInitStructure); + /* Configure the channels to be in capture/compare mode */ + for (uint8_t i = 0; i < cfg->num_channels; i++) { + const struct pios_tim_channel * chan = &cfg->channels[i]; - /* Configure timer clocks */ - TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure = pios_ppm_cfg.tim_base_init; - TIM_InternalClockConfig(pios_ppm_cfg.timer); - TIM_TimeBaseInit(pios_ppm_cfg.timer, &TIM_TimeBaseStructure); + /* Configure timer for input capture */ + TIM_ICInitTypeDef TIM_ICInitStructure = cfg->tim_ic_init; + TIM_ICInitStructure.TIM_Channel = chan->timer_chan; + TIM_ICInit(chan->timer, &TIM_ICInitStructure); - /* Enable the Capture Compare Interrupt Request */ - TIM_ITConfig(pios_ppm_cfg.timer, pios_ppm_cfg.ccr | TIM_IT_Update, ENABLE); - - /* Enable timers */ - TIM_Cmd(pios_ppm_cfg.timer, ENABLE); + /* Enable the Capture Compare Interrupt Request */ + switch (chan->timer_chan) { + case TIM_Channel_1: + TIM_ITConfig(chan->timer, TIM_IT_CC1 | TIM_IT_Update, ENABLE); + break; + case TIM_Channel_2: + TIM_ITConfig(chan->timer, TIM_IT_CC2 | TIM_IT_Update, ENABLE); + break; + case TIM_Channel_3: + TIM_ITConfig(chan->timer, TIM_IT_CC3 | TIM_IT_Update, ENABLE); + break; + case TIM_Channel_4: + TIM_ITConfig(chan->timer, TIM_IT_CC4 | TIM_IT_Update, ENABLE); + break; + } + } /* Setup local variable which stays in this scope */ /* Doing this here and using a local variable saves doing it in the ISR */ @@ -156,9 +187,16 @@ void PIOS_PPM_Init(void) TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1; TIM_ICInitStructure.TIM_ICFilter = 0x0; - if (!PIOS_RTC_RegisterTickCallback(PIOS_PPM_Supervisor, 0)) { + if (!PIOS_RTC_RegisterTickCallback(PIOS_PPM_Supervisor, (uint32_t)ppm_dev)) { PIOS_DEBUG_Assert(0); } + + *ppm_id = (uint32_t)ppm_dev; + + return(0); + +out_fail: + return(-1); } /** @@ -169,142 +207,146 @@ void PIOS_PPM_Init(void) */ static int32_t PIOS_PPM_Get(uint32_t rcvr_id, uint8_t channel) { - /* Return error if channel not available */ - if (channel >= PIOS_PPM_IN_MAX_NUM_CHANNELS) { - return -1; + struct pios_ppm_dev * ppm_dev = (struct pios_ppm_dev *)rcvr_id; + + if (!PIOS_PPM_validate(ppm_dev)) { + /* Invalid device specified */ + return PIOS_RCVR_INVALID; } - return CaptureValue[channel]; + + if (channel >= PIOS_PPM_IN_MAX_NUM_CHANNELS) { + /* Channel out of range */ + return PIOS_RCVR_INVALID; + } + return ppm_dev->CaptureValue[channel]; } -/** -* Handle TIMx global interrupt request -* Some work and testing still needed, need to detect start of frame and decode pulses -* -*/ -void PIOS_PPM_irq_handler(void) +static void PIOS_PPM_tim_overflow_cb (uint32_t tim_id, uint32_t context, uint8_t channel, uint16_t count) { - /* Timer Overflow Interrupt - * The time between timer overflows must be greater than the PPM - * frame period. If a full frame has not decoded in the between timer - * overflows then capture values should be cleared. - */ + struct pios_ppm_dev * ppm_dev = (struct pios_ppm_dev *)context; - if (TIM_GetITStatus(pios_ppm_cfg.timer, TIM_IT_Update) == SET) { - /* Clear TIMx overflow interrupt pending bit */ - TIM_ClearITPendingBit(pios_ppm_cfg.timer, TIM_IT_Update); - - /* If sharing a timer with a servo output the ARR register will - be set according to the PWM period. When timer reaches the - ARR value a timer overflow interrupt will fire. We use the - interrupt accumulate a 32-bit timer. */ - LargeCounter = LargeCounter + pios_ppm_cfg.timer->ARR; + if (!PIOS_PPM_validate(ppm_dev)) { + /* Invalid device specified */ + return; } - /* Signal edge interrupt */ - if (TIM_GetITStatus(pios_ppm_cfg.timer, pios_ppm_cfg.ccr) == SET) { - PreviousTime = CurrentTime; + ppm_dev->LargeCounter += count; - switch((int32_t) pios_ppm_cfg.ccr) { - case (int32_t)TIM_IT_CC1: - CurrentTime = TIM_GetCapture1(pios_ppm_cfg.timer); - break; - case (int32_t)TIM_IT_CC2: - CurrentTime = TIM_GetCapture2(pios_ppm_cfg.timer); - break; - case (int32_t)TIM_IT_CC3: - CurrentTime = TIM_GetCapture3(pios_ppm_cfg.timer); - break; - case (int32_t)TIM_IT_CC4: - CurrentTime = TIM_GetCapture4(pios_ppm_cfg.timer); - break; + return; +} + + +static void PIOS_PPM_tim_edge_cb (uint32_t tim_id, uint32_t context, uint8_t chan_idx, uint16_t count) +{ + /* Recover our device context */ + struct pios_ppm_dev * ppm_dev = (struct pios_ppm_dev *)context; + + if (!PIOS_PPM_validate(ppm_dev)) { + /* Invalid device specified */ + return; + } + + if (chan_idx >= ppm_dev->cfg->num_channels) { + /* Channel out of range */ + return; + } + + /* Shift the last measurement out */ + ppm_dev->PreviousTime = ppm_dev->CurrentTime; + + /* Grab the new count */ + ppm_dev->CurrentTime = count; + + /* Convert to 32-bit timer result */ + ppm_dev->CurrentTime += ppm_dev->LargeCounter; + + /* Capture computation */ + ppm_dev->DeltaTime = ppm_dev->CurrentTime - ppm_dev->PreviousTime; + + ppm_dev->PreviousTime = ppm_dev->CurrentTime; + + /* Sync pulse detection */ + if (ppm_dev->DeltaTime > PIOS_PPM_IN_MIN_SYNC_PULSE_US) { + if (ppm_dev->PulseIndex == ppm_dev->NumChannelsPrevFrame + && ppm_dev->PulseIndex >= PIOS_PPM_IN_MIN_NUM_CHANNELS + && ppm_dev->PulseIndex <= PIOS_PPM_IN_MAX_NUM_CHANNELS) + { + /* If we see n simultaneous frames of the same + number of channels we save it as our frame size */ + if (ppm_dev->NumChannelCounter < PIOS_PPM_STABLE_CHANNEL_COUNT) + ppm_dev->NumChannelCounter++; + else + ppm_dev->NumChannels = ppm_dev->PulseIndex; + } else { + ppm_dev->NumChannelCounter = 0; } - /* Clear TIMx Capture compare interrupt pending bit */ - TIM_ClearITPendingBit(pios_ppm_cfg.timer, pios_ppm_cfg.ccr); - - /* Convert to 32-bit timer result */ - CurrentTime = CurrentTime + LargeCounter; - - /* Capture computation */ - DeltaTime = CurrentTime - PreviousTime; - - PreviousTime = CurrentTime; - - /* Sync pulse detection */ - if (DeltaTime > PIOS_PPM_IN_MIN_SYNC_PULSE_US) { - if (PulseIndex == NumChannelsPrevFrame - && PulseIndex >= PIOS_PPM_IN_MIN_NUM_CHANNELS - && PulseIndex <= PIOS_PPM_IN_MAX_NUM_CHANNELS) - { - /* If we see n simultaneous frames of the same - number of channels we save it as our frame size */ - if (NumChannelCounter < PIOS_PPM_STABLE_CHANNEL_COUNT) - NumChannelCounter++; - else - NumChannels = PulseIndex; - } else { - NumChannelCounter = 0; + /* Check if the last frame was well formed */ + if (ppm_dev->PulseIndex == ppm_dev->NumChannels && ppm_dev->Tracking) { + /* The last frame was well formed */ + for (uint32_t i = 0; i < ppm_dev->NumChannels; i++) { + ppm_dev->CaptureValue[i] = ppm_dev->CaptureValueNewFrame[i]; } - - /* Check if the last frame was well formed */ - if (PulseIndex == NumChannels && Tracking) { - /* The last frame was well formed */ - for (uint32_t i = 0; i < NumChannels; i++) { - CaptureValue[i] = CaptureValueNewFrame[i]; - } - for (uint32_t i = NumChannels; - i < PIOS_PPM_IN_MAX_NUM_CHANNELS; i++) { - CaptureValue[i] = PIOS_PPM_INPUT_INVALID; - } + for (uint32_t i = ppm_dev->NumChannels; + i < PIOS_PPM_IN_MAX_NUM_CHANNELS; i++) { + ppm_dev->CaptureValue[i] = PIOS_RCVR_TIMEOUT; } + } - Fresh = TRUE; - Tracking = TRUE; - NumChannelsPrevFrame = PulseIndex; - PulseIndex = 0; + ppm_dev->Fresh = TRUE; + ppm_dev->Tracking = TRUE; + ppm_dev->NumChannelsPrevFrame = ppm_dev->PulseIndex; + ppm_dev->PulseIndex = 0; - /* We rely on the supervisor to set CaptureValue to invalid - if no valid frame is found otherwise we ride over it */ + /* We rely on the supervisor to set CaptureValue to invalid + if no valid frame is found otherwise we ride over it */ - } else if (Tracking) { - /* Valid pulse duration 0.75 to 2.5 ms*/ - if (DeltaTime > PIOS_PPM_IN_MIN_CHANNEL_PULSE_US - && DeltaTime < PIOS_PPM_IN_MAX_CHANNEL_PULSE_US - && PulseIndex < PIOS_PPM_IN_MAX_NUM_CHANNELS) { - - CaptureValueNewFrame[PulseIndex] = DeltaTime; - PulseIndex++; - } else { - /* Not a valid pulse duration */ - Tracking = FALSE; - for (uint32_t i = 0; i < PIOS_PPM_IN_MAX_NUM_CHANNELS ; i++) { - CaptureValueNewFrame[i] = PIOS_PPM_INPUT_INVALID; - } + } else if (ppm_dev->Tracking) { + /* Valid pulse duration 0.75 to 2.5 ms*/ + if (ppm_dev->DeltaTime > PIOS_PPM_IN_MIN_CHANNEL_PULSE_US + && ppm_dev->DeltaTime < PIOS_PPM_IN_MAX_CHANNEL_PULSE_US + && ppm_dev->PulseIndex < PIOS_PPM_IN_MAX_NUM_CHANNELS) { + + ppm_dev->CaptureValueNewFrame[ppm_dev->PulseIndex] = ppm_dev->DeltaTime; + ppm_dev->PulseIndex++; + } else { + /* Not a valid pulse duration */ + ppm_dev->Tracking = FALSE; + for (uint32_t i = 0; i < PIOS_PPM_IN_MAX_NUM_CHANNELS ; i++) { + ppm_dev->CaptureValueNewFrame[i] = PIOS_RCVR_TIMEOUT; } } } } static void PIOS_PPM_Supervisor(uint32_t ppm_id) { + /* Recover our device context */ + struct pios_ppm_dev * ppm_dev = (struct pios_ppm_dev *)ppm_id; + + if (!PIOS_PPM_validate(ppm_dev)) { + /* Invalid device specified */ + return; + } + /* * RTC runs at 625Hz so divide down the base rate so * that this loop runs at 25Hz. */ - if(++supv_timer < 25) { + if(++(ppm_dev->supv_timer) < 25) { return; } - supv_timer = 0; + ppm_dev->supv_timer = 0; - if (!Fresh) { - Tracking = FALSE; + if (!ppm_dev->Fresh) { + ppm_dev->Tracking = FALSE; for (int32_t i = 0; i < PIOS_PPM_IN_MAX_NUM_CHANNELS ; i++) { - CaptureValue[i] = PIOS_PPM_INPUT_INVALID; - CaptureValueNewFrame[i] = PIOS_PPM_INPUT_INVALID; + ppm_dev->CaptureValue[i] = PIOS_RCVR_TIMEOUT; + ppm_dev->CaptureValueNewFrame[i] = PIOS_RCVR_TIMEOUT; } } - Fresh = FALSE; + ppm_dev->Fresh = FALSE; } #endif diff --git a/flight/PiOS/STM32F10x/pios_pwm.c b/flight/PiOS/STM32F10x/pios_pwm.c index 433c272bb..4e7c98b14 100644 --- a/flight/PiOS/STM32F10x/pios_pwm.c +++ b/flight/PiOS/STM32F10x/pios_pwm.c @@ -42,96 +42,131 @@ const struct pios_rcvr_driver pios_pwm_rcvr_driver = { }; /* Local Variables */ -static uint8_t CaptureState[PIOS_PWM_NUM_INPUTS]; -static uint16_t RiseValue[PIOS_PWM_NUM_INPUTS]; -static uint16_t FallValue[PIOS_PWM_NUM_INPUTS]; -static uint32_t CaptureValue[PIOS_PWM_NUM_INPUTS]; +/* 100 ms timeout without updates on channels */ +const static uint32_t PWM_SUPERVISOR_TIMEOUT = 100000; -static uint32_t CapCounter[PIOS_PWM_NUM_INPUTS]; +enum pios_pwm_dev_magic { + PIOS_PWM_DEV_MAGIC = 0xab30293c, +}; + +struct pios_pwm_dev { + enum pios_pwm_dev_magic magic; + const struct pios_pwm_cfg * cfg; + + uint8_t CaptureState[PIOS_PWM_NUM_INPUTS]; + uint16_t RiseValue[PIOS_PWM_NUM_INPUTS]; + uint16_t FallValue[PIOS_PWM_NUM_INPUTS]; + uint32_t CaptureValue[PIOS_PWM_NUM_INPUTS]; + uint32_t CapCounter[PIOS_PWM_NUM_INPUTS]; + uint32_t us_since_update[PIOS_PWM_NUM_INPUTS]; +}; + +static bool PIOS_PWM_validate(struct pios_pwm_dev * pwm_dev) +{ + return (pwm_dev->magic == PIOS_PWM_DEV_MAGIC); +} + +#if defined(PIOS_INCLUDE_FREERTOS) +static struct pios_pwm_dev * PIOS_PWM_alloc(void) +{ + struct pios_pwm_dev * pwm_dev; + + pwm_dev = (struct pios_pwm_dev *)pvPortMalloc(sizeof(*pwm_dev)); + if (!pwm_dev) return(NULL); + + pwm_dev->magic = PIOS_PWM_DEV_MAGIC; + return(pwm_dev); +} +#else +static struct pios_pwm_dev pios_pwm_devs[PIOS_PWM_MAX_DEVS]; +static uint8_t pios_pwm_num_devs; +static struct pios_pwm_dev * PIOS_PWM_alloc(void) +{ + struct pios_pwm_dev * pwm_dev; + + if (pios_pwm_num_devs >= PIOS_PWM_MAX_DEVS) { + return (NULL); + } + + pwm_dev = &pios_pwm_devs[pios_pwm_num_devs++]; + pwm_dev->magic = PIOS_PWM_DEV_MAGIC; + + return (pwm_dev); +} +#endif + +static void PIOS_PWM_tim_overflow_cb (uint32_t id, uint32_t context, uint8_t channel, uint16_t count); +static void PIOS_PWM_tim_edge_cb (uint32_t id, uint32_t context, uint8_t channel, uint16_t count); +const static struct pios_tim_callbacks tim_callbacks = { + .overflow = PIOS_PWM_tim_overflow_cb, + .edge = PIOS_PWM_tim_edge_cb, +}; /** * Initialises all the pins */ -void PIOS_PWM_Init(void) +int32_t PIOS_PWM_Init(uint32_t * pwm_id, const struct pios_pwm_cfg * cfg) { - for (uint8_t i = 0; i < pios_pwm_cfg.num_channels; i++) { - /* Flush counter variables */ - CaptureState[i] = 0; - RiseValue[i] = 0; - FallValue[i] = 0; - CaptureValue[i] = 0; - - NVIC_InitTypeDef NVIC_InitStructure = pios_pwm_cfg.irq.init; - GPIO_InitTypeDef GPIO_InitStructure = pios_pwm_cfg.gpio_init; - TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure = pios_pwm_cfg.tim_base_init; - TIM_ICInitTypeDef TIM_ICInitStructure = pios_pwm_cfg.tim_ic_init; - - struct pios_pwm_channel channel = pios_pwm_cfg.channels[i]; - - /* Enable appropriate clock to timer module */ - switch((int32_t) channel.timer) { - case (int32_t)TIM1: - NVIC_InitStructure.NVIC_IRQChannel = TIM1_CC_IRQn; - RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1, ENABLE); - break; - case (int32_t)TIM2: - NVIC_InitStructure.NVIC_IRQChannel = TIM2_IRQn; - RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE); - break; - case (int32_t)TIM3: - NVIC_InitStructure.NVIC_IRQChannel = TIM3_IRQn; - RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE); - break; - case (int32_t)TIM4: - NVIC_InitStructure.NVIC_IRQChannel = TIM4_IRQn; - RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM4, ENABLE); - break; -#ifdef STM32F10X_HD - - case (int32_t)TIM5: - NVIC_InitStructure.NVIC_IRQChannel = TIM5_IRQn; - RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM5, ENABLE); - break; - case (int32_t)TIM6: - NVIC_InitStructure.NVIC_IRQChannel = TIM6_IRQn; - RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM6, ENABLE); - break; - case (int32_t)TIM7: - NVIC_InitStructure.NVIC_IRQChannel = TIM7_IRQn; - RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM7, ENABLE); - break; - case (int32_t)TIM8: - NVIC_InitStructure.NVIC_IRQChannel = TIM8_CC_IRQn; - RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM8, ENABLE); - break; -#endif - } - NVIC_Init(&NVIC_InitStructure); + PIOS_DEBUG_Assert(pwm_id); + PIOS_DEBUG_Assert(cfg); + + struct pios_pwm_dev * pwm_dev; + + pwm_dev = (struct pios_pwm_dev *) PIOS_PWM_alloc(); + if (!pwm_dev) goto out_fail; + + /* Bind the configuration to the device instance */ + pwm_dev->cfg = cfg; + + for (uint8_t i = 0; i < PIOS_PWM_NUM_INPUTS; i++) { + /* Flush counter variables */ + pwm_dev->CaptureState[i] = 0; + pwm_dev->RiseValue[i] = 0; + pwm_dev->FallValue[i] = 0; + pwm_dev->CaptureValue[i] = PIOS_RCVR_TIMEOUT; + } + + uint32_t tim_id; + if (PIOS_TIM_InitChannels(&tim_id, cfg->channels, cfg->num_channels, &tim_callbacks, (uint32_t)pwm_dev)) { + return -1; + } + + /* Configure the channels to be in capture/compare mode */ + for (uint8_t i = 0; i < cfg->num_channels; i++) { + const struct pios_tim_channel * chan = &cfg->channels[i]; - /* Enable GPIO */ - GPIO_InitStructure.GPIO_Pin = channel.pin; - GPIO_Init(channel.port, &GPIO_InitStructure); - /* Configure timer for input capture */ - TIM_ICInitStructure.TIM_Channel = channel.channel; - TIM_ICInit(channel.timer, &TIM_ICInitStructure); - - /* Configure timer clocks */ - TIM_InternalClockConfig(channel.timer); - if(channel.timer->PSC != ((PIOS_MASTER_CLOCK / 1000000) - 1)) - TIM_TimeBaseInit(channel.timer, &TIM_TimeBaseStructure); + TIM_ICInitTypeDef TIM_ICInitStructure = cfg->tim_ic_init; + TIM_ICInitStructure.TIM_Channel = chan->timer_chan; + TIM_ICInit(chan->timer, &TIM_ICInitStructure); /* Enable the Capture Compare Interrupt Request */ - TIM_ITConfig(channel.timer, channel.ccr, ENABLE); + switch (chan->timer_chan) { + case TIM_Channel_1: + TIM_ITConfig(chan->timer, TIM_IT_CC1, ENABLE); + break; + case TIM_Channel_2: + TIM_ITConfig(chan->timer, TIM_IT_CC2, ENABLE); + break; + case TIM_Channel_3: + TIM_ITConfig(chan->timer, TIM_IT_CC3, ENABLE); + break; + case TIM_Channel_4: + TIM_ITConfig(chan->timer, TIM_IT_CC4, ENABLE); + break; + } + + // Need the update event for that timer to detect timeouts + TIM_ITConfig(chan->timer, TIM_IT_Update, ENABLE); - /* Enable timers */ - TIM_Cmd(channel.timer, ENABLE); } - if(pios_pwm_cfg.remap) { - /* Warning, I don't think this will work for multiple remaps at once */ - GPIO_PinRemapConfig(pios_pwm_cfg.remap, ENABLE); - } + *pwm_id = (uint32_t) pwm_dev; + + return (0); + +out_fail: + return (-1); } /** @@ -142,75 +177,101 @@ void PIOS_PWM_Init(void) */ static int32_t PIOS_PWM_Get(uint32_t rcvr_id, uint8_t channel) { - /* Return error if channel not available */ - if (channel >= pios_pwm_cfg.num_channels) { - return -1; + struct pios_pwm_dev * pwm_dev = (struct pios_pwm_dev *)rcvr_id; + + if (!PIOS_PWM_validate(pwm_dev)) { + /* Invalid device specified */ + return PIOS_RCVR_INVALID; } - return CaptureValue[channel]; + + if (channel >= PIOS_PWM_NUM_INPUTS) { + /* Channel out of range */ + return PIOS_RCVR_INVALID; + } + return pwm_dev->CaptureValue[channel]; } -void PIOS_PWM_irq_handler(TIM_TypeDef * timer) +static void PIOS_PWM_tim_overflow_cb (uint32_t tim_id, uint32_t context, uint8_t channel, uint16_t count) { - 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); - } - } + struct pios_pwm_dev * pwm_dev = (struct pios_pwm_dev *)context; + + if (!PIOS_PWM_validate(pwm_dev)) { + /* Invalid device specified */ + return; } + + if (channel >= pwm_dev->cfg->num_channels) { + /* Channel out of range */ + return; + } + + pwm_dev->us_since_update[channel] += count; + if(pwm_dev->us_since_update[channel] >= PWM_SUPERVISOR_TIMEOUT) { + pwm_dev->CaptureState[channel] = 0; + pwm_dev->RiseValue[channel] = 0; + pwm_dev->FallValue[channel] = 0; + pwm_dev->CaptureValue[channel] = PIOS_RCVR_TIMEOUT; + pwm_dev->us_since_update[channel] = 0; + } + + return; +} + +static void PIOS_PWM_tim_edge_cb (uint32_t tim_id, uint32_t context, uint8_t chan_idx, uint16_t count) +{ + /* Recover our device context */ + struct pios_pwm_dev * pwm_dev = (struct pios_pwm_dev *)context; + + if (!PIOS_PWM_validate(pwm_dev)) { + /* Invalid device specified */ + return; + } + + if (chan_idx >= pwm_dev->cfg->num_channels) { + /* Channel out of range */ + return; + } + + const struct pios_tim_channel * chan = &pwm_dev->cfg->channels[chan_idx]; + + if (pwm_dev->CaptureState[chan_idx] == 0) { + pwm_dev->RiseValue[chan_idx] = count; + pwm_dev->us_since_update[chan_idx] = 0; + } else { + pwm_dev->FallValue[chan_idx] = count; + } + + // flip state machine and capture value here + /* Simple rise or fall state machine */ + TIM_ICInitTypeDef TIM_ICInitStructure = pwm_dev->cfg->tim_ic_init; + if (pwm_dev->CaptureState[chan_idx] == 0) { + /* Switch states */ + pwm_dev->CaptureState[chan_idx] = 1; + + /* Switch polarity of input capture */ + TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Falling; + TIM_ICInitStructure.TIM_Channel = chan->timer_chan; + TIM_ICInit(chan->timer, &TIM_ICInitStructure); + } else { + /* Capture computation */ + if (pwm_dev->FallValue[chan_idx] > pwm_dev->RiseValue[chan_idx]) { + pwm_dev->CaptureValue[chan_idx] = (pwm_dev->FallValue[chan_idx] - pwm_dev->RiseValue[chan_idx]); + } else { + pwm_dev->CaptureValue[chan_idx] = ((chan->timer->ARR - pwm_dev->RiseValue[chan_idx]) + pwm_dev->FallValue[chan_idx]); + } + + /* Switch states */ + pwm_dev->CaptureState[chan_idx] = 0; + + /* Increase supervisor counter */ + pwm_dev->CapCounter[chan_idx]++; + + /* Switch polarity of input capture */ + TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Rising; + TIM_ICInitStructure.TIM_Channel = chan->timer_chan; + TIM_ICInit(chan->timer, &TIM_ICInitStructure); + } + } #endif diff --git a/flight/PiOS/STM32F10x/pios_sbus.c b/flight/PiOS/STM32F10x/pios_sbus.c index a80fe8fe3..543da364b 100644 --- a/flight/PiOS/STM32F10x/pios_sbus.c +++ b/flight/PiOS/STM32F10x/pios_sbus.c @@ -59,7 +59,7 @@ static void PIOS_SBUS_Supervisor(uint32_t sbus_id); static void reset_channels(void) { for (int i = 0; i < SBUS_NUMBER_OF_CHANNELS; i++) { - channel_data[i] = 0; + channel_data[i] = PIOS_RCVR_TIMEOUT; } } @@ -183,7 +183,7 @@ static int32_t PIOS_SBUS_Get(uint32_t rcvr_id, uint8_t channel) { /* return error if channel is not available */ if (channel >= SBUS_NUMBER_OF_CHANNELS) { - return -1; + return PIOS_RCVR_INVALID; } return channel_data[channel]; } diff --git a/flight/PiOS/STM32F10x/pios_servo.c b/flight/PiOS/STM32F10x/pios_servo.c index 229f371ce..cb7d98292 100644 --- a/flight/PiOS/STM32F10x/pios_servo.c +++ b/flight/PiOS/STM32F10x/pios_servo.c @@ -31,97 +31,55 @@ /* Project Includes */ #include "pios.h" #include "pios_servo_priv.h" +#include "pios_tim_priv.h" /* Private Function Prototypes */ +static const struct pios_servo_cfg * servo_cfg; + /** * Initialise Servos */ -void PIOS_Servo_Init(void) +int32_t PIOS_Servo_Init(const struct pios_servo_cfg * cfg) { -#ifndef PIOS_ENABLE_DEBUG_PINS -#if defined(PIOS_INCLUDE_SERVO) + uint32_t tim_id; + if (PIOS_TIM_InitChannels(&tim_id, cfg->channels, cfg->num_channels, NULL, 0)) { + return -1; + } + /* Store away the requested configuration */ + servo_cfg = cfg; - for (uint8_t i = 0; i < pios_servo_cfg.num_channels; i++) { - GPIO_InitTypeDef GPIO_InitStructure = pios_servo_cfg.gpio_init; - TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure = pios_servo_cfg.tim_base_init; - TIM_OCInitTypeDef TIM_OCInitStructure = pios_servo_cfg.tim_oc_init; - - struct pios_servo_channel channel = pios_servo_cfg.channels[i]; - - /* Enable appropriate clock to timer module */ - switch((int32_t) channel.timer) { - case (int32_t)TIM1: - RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1, ENABLE); - break; - case (int32_t)TIM2: - RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE); - break; - case (int32_t)TIM3: - RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE); - break; - case (int32_t)TIM4: - RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM4, ENABLE); - break; - case (int32_t)TIM5: - RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM5, ENABLE); - break; - case (int32_t)TIM6: - RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM6, ENABLE); - break; - case (int32_t)TIM7: - RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM7, ENABLE); - break; - case (int32_t)TIM8: - RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM8, ENABLE); - break; - } - - /* Enable GPIO */ - GPIO_InitStructure.GPIO_Pin = channel.pin; - GPIO_Init(channel.port, &GPIO_InitStructure); - - /* Enable time base */ - TIM_TimeBaseInit(channel.timer, &TIM_TimeBaseStructure); - - channel.timer->PSC = (PIOS_MASTER_CLOCK / 1000000) - 1; + /* Configure the channels to be in output compare mode */ + for (uint8_t i = 0; i < cfg->num_channels; i++) { + const struct pios_tim_channel * chan = &cfg->channels[i]; /* Set up for output compare function */ - switch(channel.channel) { + switch(chan->timer_chan) { case TIM_Channel_1: - TIM_OC1Init(channel.timer, &TIM_OCInitStructure); - TIM_OC1PreloadConfig(channel.timer, TIM_OCPreload_Enable); + TIM_OC1Init(chan->timer, &cfg->tim_oc_init); + TIM_OC1PreloadConfig(chan->timer, TIM_OCPreload_Enable); break; case TIM_Channel_2: - TIM_OC2Init(channel.timer, &TIM_OCInitStructure); - TIM_OC2PreloadConfig(channel.timer, TIM_OCPreload_Enable); + TIM_OC2Init(chan->timer, &cfg->tim_oc_init); + TIM_OC2PreloadConfig(chan->timer, TIM_OCPreload_Enable); break; case TIM_Channel_3: - TIM_OC3Init(channel.timer, &TIM_OCInitStructure); - TIM_OC3PreloadConfig(channel.timer, TIM_OCPreload_Enable); + TIM_OC3Init(chan->timer, &cfg->tim_oc_init); + TIM_OC3PreloadConfig(chan->timer, TIM_OCPreload_Enable); break; case TIM_Channel_4: - TIM_OC4Init(channel.timer, &TIM_OCInitStructure); - TIM_OC4PreloadConfig(channel.timer, TIM_OCPreload_Enable); + TIM_OC4Init(chan->timer, &cfg->tim_oc_init); + TIM_OC4PreloadConfig(chan->timer, TIM_OCPreload_Enable); break; } - RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE); - TIM_ARRPreloadConfig(channel.timer, ENABLE); - TIM_CtrlPWMOutputs(channel.timer, ENABLE); - TIM_Cmd(channel.timer, ENABLE); - + TIM_ARRPreloadConfig(chan->timer, ENABLE); + TIM_CtrlPWMOutputs(chan->timer, ENABLE); + TIM_Cmd(chan->timer, ENABLE); } - if(pios_servo_cfg.remap) { - /* Warning, I don't think this will work for multiple remaps at once */ - GPIO_PinRemapConfig(pios_servo_cfg.remap, ENABLE); - } - - -#endif // PIOS_INCLUDE_SERVO -#endif // PIOS_ENABLE_DEBUG_PINS + return 0; } /** @@ -131,31 +89,31 @@ void PIOS_Servo_Init(void) */ void PIOS_Servo_SetHz(uint16_t * speeds, uint8_t banks) { -#ifndef PIOS_ENABLE_DEBUG_PINS -#if defined(PIOS_INCLUDE_SERVO) - TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure = pios_servo_cfg.tim_base_init; + if (!servo_cfg) { + return; + } + + TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure = servo_cfg->tim_base_init; TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1; TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; TIM_TimeBaseStructure.TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1; uint8_t set = 0; - for(uint8_t i = 0; (i < pios_servo_cfg.num_channels) && (set < banks); i++) { + for(uint8_t i = 0; (i < servo_cfg->num_channels) && (set < banks); i++) { bool new = true; - struct pios_servo_channel channel = pios_servo_cfg.channels[i]; + const struct pios_tim_channel * chan = &servo_cfg->channels[i]; /* See if any previous channels use that same timer */ for(uint8_t j = 0; (j < i) && new; j++) - new &= channel.timer != pios_servo_cfg.channels[j].timer; + new &= chan->timer != servo_cfg->channels[j].timer; if(new) { TIM_TimeBaseStructure.TIM_Period = ((1000000 / speeds[set]) - 1); - TIM_TimeBaseInit(channel.timer, &TIM_TimeBaseStructure); + TIM_TimeBaseInit(chan->timer, &TIM_TimeBaseStructure); set++; } } -#endif // PIOS_INCLUDE_SERVO -#endif // PIOS_ENABLE_DEBUG_PINS } /** @@ -163,29 +121,27 @@ void PIOS_Servo_SetHz(uint16_t * speeds, uint8_t banks) * \param[in] Servo Servo number (0-7) * \param[in] Position Servo position in microseconds */ -void PIOS_Servo_Set(uint8_t Servo, uint16_t Position) +void PIOS_Servo_Set(uint8_t servo, uint16_t position) { -#ifndef PIOS_ENABLE_DEBUG_PINS -#if defined(PIOS_INCLUDE_SERVO) /* Make sure servo exists */ - if (Servo < pios_servo_cfg.num_channels && Servo >= 0) { - /* Update the position */ - - switch(pios_servo_cfg.channels[Servo].channel) { - case TIM_Channel_1: - TIM_SetCompare1(pios_servo_cfg.channels[Servo].timer, Position); - break; - case TIM_Channel_2: - TIM_SetCompare2(pios_servo_cfg.channels[Servo].timer, Position); - break; - case TIM_Channel_3: - TIM_SetCompare3(pios_servo_cfg.channels[Servo].timer, Position); - break; - case TIM_Channel_4: - TIM_SetCompare4(pios_servo_cfg.channels[Servo].timer, Position); - break; - } + if (!servo_cfg || servo >= servo_cfg->num_channels) { + return; + } + + /* Update the position */ + const struct pios_tim_channel * chan = &servo_cfg->channels[servo]; + switch(chan->timer_chan) { + case TIM_Channel_1: + TIM_SetCompare1(chan->timer, position); + break; + case TIM_Channel_2: + TIM_SetCompare2(chan->timer, position); + break; + case TIM_Channel_3: + TIM_SetCompare3(chan->timer, position); + break; + case TIM_Channel_4: + TIM_SetCompare4(chan->timer, position); + break; } -#endif // PIOS_INCLUDE_SERVO -#endif // PIOS_ENABLE_DEBUG_PINS } diff --git a/flight/PiOS/STM32F10x/pios_spektrum.c b/flight/PiOS/STM32F10x/pios_spektrum.c index 8b0f38c6b..7ab8abcf3 100644 --- a/flight/PiOS/STM32F10x/pios_spektrum.c +++ b/flight/PiOS/STM32F10x/pios_spektrum.c @@ -8,7 +8,6 @@ * * @file pios_spektrum.c * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) * @brief USART commands. Inits USARTs, controls USARTs & Interrupt handlers. (STM32 dependent) * @see The GNU Public License (GPL) Version 3 * @@ -31,10 +30,11 @@ /* Project Includes */ #include "pios.h" -#include "pios_spektrum_priv.h" #if defined(PIOS_INCLUDE_SPEKTRUM) +#include "pios_spektrum_priv.h" + /** * @Note Framesyncing: * The code resets the watchdog timer whenever a single byte is received, so what watchdog code @@ -52,22 +52,80 @@ const struct pios_rcvr_driver pios_spektrum_rcvr_driver = { .read = PIOS_SPEKTRUM_Get, }; -/* Local Variables */ -static uint16_t CaptureValue[PIOS_SPEKTRUM_NUM_INPUTS],CaptureValueTemp[PIOS_SPEKTRUM_NUM_INPUTS]; -static uint8_t prev_byte = 0xFF, sync = 0, bytecount = 0, datalength=0, frame_error=0, byte_array[20] = { 0 }; -uint8_t sync_of = 0; -uint16_t supv_timer=0; +enum pios_spektrum_dev_magic { + PIOS_SPEKTRUM_DEV_MAGIC = 0xa9b9c9d9, +}; + +struct pios_spektrum_fsm { + uint16_t channel; + uint16_t CaptureValue[PIOS_SPEKTRUM_NUM_INPUTS]; + uint16_t CaptureValueTemp[PIOS_SPEKTRUM_NUM_INPUTS]; + uint8_t prev_byte; + uint8_t sync; + uint8_t bytecount; + uint8_t datalength; + uint8_t frame_error; + uint8_t sync_of; +}; + +struct pios_spektrum_dev { + enum pios_spektrum_dev_magic magic; + const struct pios_spektrum_cfg * cfg; + + struct pios_spektrum_fsm fsm; + + uint16_t supv_timer; +}; + +static bool PIOS_SPEKTRUM_validate(struct pios_spektrum_dev * spektrum_dev) +{ + return (spektrum_dev->magic == PIOS_SPEKTRUM_DEV_MAGIC); +} + +#if defined(PIOS_INCLUDE_FREERTOS) +static struct pios_spektrum_dev * PIOS_SPEKTRUM_alloc(void) +{ + struct pios_spektrum_dev * spektrum_dev; + + spektrum_dev = (struct pios_spektrum_dev *)pvPortMalloc(sizeof(*spektrum_dev)); + if (!spektrum_dev) return(NULL); + + spektrum_dev->magic = PIOS_SPEKTRUM_DEV_MAGIC; + return(spektrum_dev); +} +#else +static struct pios_spektrum_dev pios_spektrum_devs[PIOS_SPEKTRUM_MAX_DEVS]; +static uint8_t pios_spektrum_num_devs; +static struct pios_spektrum_dev * PIOS_SPEKTRUM_alloc(void) +{ + struct pios_spektrum_dev * spektrum_dev; + + if (pios_spektrum_num_devs >= PIOS_SPEKTRUM_MAX_DEVS) { + return (NULL); + } + + spektrum_dev = &pios_spektrum_devs[pios_spektrum_num_devs++]; + spektrum_dev->magic = PIOS_SPEKTRUM_DEV_MAGIC; + + return (spektrum_dev); +} +#endif static void PIOS_SPEKTRUM_Supervisor(uint32_t spektrum_id); -static bool PIOS_SPEKTRUM_Bind(const struct pios_spektrum_cfg * cfg); -static int32_t PIOS_SPEKTRUM_Decode(uint8_t b); +static bool PIOS_SPEKTRUM_Bind(const struct pios_spektrum_cfg * cfg, uint8_t bind); +static int32_t PIOS_SPEKTRUM_UpdateFSM(struct pios_spektrum_fsm * fsm, uint8_t b); static uint16_t PIOS_SPEKTRUM_RxInCallback(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, bool * need_yield) { + struct pios_spektrum_dev * spektrum_dev = (struct pios_spektrum_dev *)context; + + bool valid = PIOS_SPEKTRUM_validate(spektrum_dev); + PIOS_Assert(valid); + /* process byte(s) and clear receive timer */ for (uint8_t i = 0; i < buf_len; i++) { - PIOS_SPEKTRUM_Decode(buf[i]); - supv_timer = 0; + PIOS_SPEKTRUM_UpdateFSM(&(spektrum_dev->fsm), buf[i]); + spektrum_dev->supv_timer = 0; } /* Always signal that we can accept another byte */ @@ -82,23 +140,114 @@ static uint16_t PIOS_SPEKTRUM_RxInCallback(uint32_t context, uint8_t * buf, uint return (buf_len); } +static void PIOS_SPEKTRUM_ResetFSM(struct pios_spektrum_fsm * fsm) +{ + fsm->channel = 0; + fsm->prev_byte = 0xFF; + fsm->sync = 0; + fsm->bytecount = 0; + fsm->datalength = 0; + fsm->frame_error = 0; + fsm->sync_of = 0; +} + +/** +* Decodes a byte +* \param[in] b byte which should be spektrum decoded +* \return 0 if no error +* \return -1 if USART not available +* \return -2 if buffer full (retry) +*/ +static int32_t PIOS_SPEKTRUM_UpdateFSM(struct pios_spektrum_fsm * fsm, uint8_t b) +{ + fsm->bytecount++; + if (fsm->sync == 0) { + /* Known sync bytes, 0x01, 0x02, 0x12, 0xb2 */ + /* 0xb2 DX8 3bind pulses only */ + if (fsm->bytecount == 2) { + if ((b == 0x01) || (b == 0x02) || (b == 0xb2)) { + fsm->datalength=0; // 10bit + fsm->sync = 1; + fsm->bytecount = 2; + } + else if(b == 0x12) { + fsm->datalength=1; // 11bit + fsm->sync = 1; + fsm->bytecount = 2; + } + else + { + fsm->bytecount = 0; + } + } + } else { + if ((fsm->bytecount % 2) == 0) { + uint16_t data; + uint8_t channeln; + + fsm->channel = (fsm->prev_byte << 8) + b; + channeln = (fsm->channel >> (10+fsm->datalength)) & 0x0F; + data = fsm->channel & (0x03FF+(0x0400*fsm->datalength)); + if(channeln==0 && data<10) // discard frame if throttle misbehaves + { + fsm->frame_error=1; + } + if (channeln < PIOS_SPEKTRUM_NUM_INPUTS && !fsm->frame_error) + fsm->CaptureValueTemp[channeln] = data; + } + } + if (fsm->bytecount == 16) { + fsm->bytecount = 0; + fsm->sync = 0; + fsm->sync_of = 0; + if (!fsm->frame_error) + { + for(int i=0;iCaptureValue[i] = fsm->CaptureValueTemp[i]; + } + } + fsm->frame_error=0; + } + fsm->prev_byte = b; + return 0; +} + /** * Bind and Initialise Spektrum satellite receiver */ -int32_t PIOS_SPEKTRUM_Init(uint32_t * spektrum_id, const struct pios_spektrum_cfg *cfg, const struct pios_com_driver * driver, uint32_t lower_id, bool bind) +int32_t PIOS_SPEKTRUM_Init(uint32_t * spektrum_id, const struct pios_spektrum_cfg *cfg, const struct pios_com_driver * driver, uint32_t lower_id, uint8_t bind) { - // TODO: need setting flag for bind on next powerup + PIOS_DEBUG_Assert(spektrum_id); + PIOS_DEBUG_Assert(cfg); + PIOS_DEBUG_Assert(driver); + + struct pios_spektrum_dev * spektrum_dev; + + spektrum_dev = (struct pios_spektrum_dev *) PIOS_SPEKTRUM_alloc(); + if (!spektrum_dev) goto out_fail; + + /* Bind the configuration to the device instance */ + spektrum_dev->cfg = cfg; + if (bind) { - PIOS_SPEKTRUM_Bind(cfg); + PIOS_SPEKTRUM_Bind(cfg,bind); } - (driver->bind_rx_cb)(lower_id, PIOS_SPEKTRUM_RxInCallback, 0); + PIOS_SPEKTRUM_ResetFSM(&(spektrum_dev->fsm)); - if (!PIOS_RTC_RegisterTickCallback(PIOS_SPEKTRUM_Supervisor, 0)) { + *spektrum_id = (uint32_t)spektrum_dev; + + (driver->bind_rx_cb)(lower_id, PIOS_SPEKTRUM_RxInCallback, *spektrum_id); + + if (!PIOS_RTC_RegisterTickCallback(PIOS_SPEKTRUM_Supervisor, *spektrum_id)) { PIOS_DEBUG_Assert(0); } return (0); + +out_fail: + return(-1); } /** @@ -109,11 +258,16 @@ int32_t PIOS_SPEKTRUM_Init(uint32_t * spektrum_id, const struct pios_spektrum_cf */ static int32_t PIOS_SPEKTRUM_Get(uint32_t rcvr_id, uint8_t channel) { + struct pios_spektrum_dev * spektrum_dev = (struct pios_spektrum_dev *)rcvr_id; + + if(!PIOS_SPEKTRUM_validate(spektrum_dev)) + return PIOS_RCVR_INVALID; + /* Return error if channel not available */ if (channel >= PIOS_SPEKTRUM_NUM_INPUTS) { - return -1; + return PIOS_RCVR_INVALID; } - return CaptureValue[channel]; + return spektrum_dev->fsm.CaptureValue[channel]; } /** @@ -121,9 +275,15 @@ static int32_t PIOS_SPEKTRUM_Get(uint32_t rcvr_id, uint8_t channel) * \output true Successful bind * \output false Bind failed */ -static bool PIOS_SPEKTRUM_Bind(const struct pios_spektrum_cfg * cfg) +static bool PIOS_SPEKTRUM_Bind(const struct pios_spektrum_cfg * cfg, uint8_t bind) { -#define BIND_PULSES 5 + GPIO_InitTypeDef GPIO_InitStructure; + GPIO_InitStructure.GPIO_Pin = cfg->bind.init.GPIO_Pin; + GPIO_InitStructure.GPIO_Speed = cfg->bind.init.GPIO_Speed; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU; + + /* just to limit bind pulses */ + bind=(bind<=10)?bind:10; GPIO_Init(cfg->bind.gpio, &cfg->bind.init); /* RX line, set high */ @@ -132,7 +292,7 @@ static bool PIOS_SPEKTRUM_Bind(const struct pios_spektrum_cfg * cfg) /* on CC works upto 140ms, I guess bind window is around 20-140ms after powerup */ PIOS_DELAY_WaitmS(60); - for (int i = 0; i < BIND_PULSES ; i++) { + for (int i = 0; i < bind ; i++) { /* RX line, drive low for 120us */ GPIO_ResetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin); PIOS_DELAY_WaituS(120); @@ -141,118 +301,44 @@ static bool PIOS_SPEKTRUM_Bind(const struct pios_spektrum_cfg * cfg) PIOS_DELAY_WaituS(120); } /* RX line, set input and wait for data, PIOS_SPEKTRUM_Init */ + GPIO_Init(cfg->bind.gpio, &GPIO_InitStructure); return true; } -/** -* Decodes a byte -* \param[in] b byte which should be spektrum decoded -* \return 0 if no error -* \return -1 if USART not available -* \return -2 if buffer full (retry) -* \note Applications shouldn't call these functions directly -*/ -static int32_t PIOS_SPEKTRUM_Decode(uint8_t b) -{ - static uint16_t channel = 0; /*, sync_word = 0;*/ - uint8_t channeln = 0, frame = 0; - uint16_t data = 0; - byte_array[bytecount] = b; - bytecount++; - if (sync == 0) { - //sync_word = (prev_byte << 8) + b; -#if 0 - /* maybe create object to show this data */ - if(bytecount==1) - { - /* record losscounter into channel8 */ - CaptureValueTemp[7]=b; - /* instant write */ - CaptureValue[7]=b; - } -#endif - /* Known sync bytes, 0x01, 0x02, 0x12 */ - if (bytecount == 2) { - if (b == 0x01) { - datalength=0; // 10bit - //frames=1; - sync = 1; - bytecount = 2; - } - else if(b == 0x02) { - datalength=0; // 10bit - //frames=2; - sync = 1; - bytecount = 2; - } - else if(b == 0x12) { - datalength=1; // 11bit - //frames=2; - sync = 1; - bytecount = 2; - } - else - { - bytecount = 0; - } - } - } else { - if ((bytecount % 2) == 0) { - channel = (prev_byte << 8) + b; - frame = channel >> 15; - channeln = (channel >> (10+datalength)) & 0x0F; - data = channel & (0x03FF+(0x0400*datalength)); - if(channeln==0 && data<10) // discard frame if throttle misbehaves - { - frame_error=1; - } - if (channeln < PIOS_SPEKTRUM_NUM_INPUTS && !frame_error) - CaptureValueTemp[channeln] = data; - } - } - if (bytecount == 16) { - //PIOS_COM_SendBufferNonBlocking(PIOS_COM_TELEM_RF,byte_array,16); //00 2c 58 84 b0 dc ff - bytecount = 0; - sync = 0; - sync_of = 0; - if (!frame_error) - { - for(int i=0;i 5) { +static void PIOS_SPEKTRUM_Supervisor(uint32_t spektrum_id) +{ + struct pios_spektrum_dev * spektrum_dev = (struct pios_spektrum_dev *)spektrum_id; + + bool valid = PIOS_SPEKTRUM_validate(spektrum_dev); + PIOS_Assert(valid); + + /* 625hz */ + spektrum_dev->supv_timer++; + if(spektrum_dev->supv_timer > 4) { /* sync between frames */ - sync = 0; - bytecount = 0; - prev_byte = 0xFF; - frame_error = 0; - sync_of++; - /* watchdog activated after 100ms silence */ - if (sync_of > 12) { + struct pios_spektrum_fsm * fsm = &(spektrum_dev->fsm); + + fsm->sync = 0; + fsm->bytecount = 0; + fsm->prev_byte = 0xFF; + fsm->frame_error = 0; + fsm->sync_of++; + /* watchdog activated after 200ms silence */ + if (fsm->sync_of > 30) { + /* signal lost */ - sync_of = 0; + fsm->sync_of = 0; for (int i = 0; i < PIOS_SPEKTRUM_NUM_INPUTS; i++) { - CaptureValue[i] = 0; - CaptureValueTemp[i] = 0; + fsm->CaptureValue[i] = PIOS_RCVR_TIMEOUT; + fsm->CaptureValueTemp[i] = PIOS_RCVR_TIMEOUT; } } - supv_timer = 0; + spektrum_dev->supv_timer = 0; } } diff --git a/flight/PiOS/STM32F10x/pios_spi.c b/flight/PiOS/STM32F10x/pios_spi.c index e69612821..6f9b62227 100644 --- a/flight/PiOS/STM32F10x/pios_spi.c +++ b/flight/PiOS/STM32F10x/pios_spi.c @@ -46,10 +46,10 @@ static bool PIOS_SPI_validate(struct pios_spi_dev * com_dev) return(true); } -#if defined(PIOS_INCLUDE_FREERTOS) && 0 +#if defined(PIOS_INCLUDE_FREERTOS) static struct pios_spi_dev * PIOS_SPI_alloc(void) { - return (malloc(sizeof(struct pios_spi_dev))); + return (pvPortMalloc(sizeof(struct pios_spi_dev))); } #else static struct pios_spi_dev pios_spi_devs[PIOS_SPI_MAX_DEVS]; diff --git a/flight/PiOS/STM32F10x/pios_tim.c b/flight/PiOS/STM32F10x/pios_tim.c new file mode 100644 index 000000000..345c9e36e --- /dev/null +++ b/flight/PiOS/STM32F10x/pios_tim.c @@ -0,0 +1,391 @@ +#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; + } + GPIO_Init(chan->pin.gpio, &chan->pin.init); + + 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 + */ +static void PIOS_TIM_1_irq_handler (void) +{ + PIOS_TIM_generic_irq_handler (TIM1); +} +void TIM1_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_1_irq_handler"))); + +static void PIOS_TIM_2_irq_handler (void) +{ + PIOS_TIM_generic_irq_handler (TIM2); +} +void TIM2_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_2_irq_handler"))); + +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); +} + diff --git a/flight/PiOS/STM32F10x/pios_usart.c b/flight/PiOS/STM32F10x/pios_usart.c index 8582344b5..68a9265ee 100644 --- a/flight/PiOS/STM32F10x/pios_usart.c +++ b/flight/PiOS/STM32F10x/pios_usart.c @@ -70,12 +70,12 @@ static bool PIOS_USART_validate(struct pios_usart_dev * usart_dev) return (usart_dev->magic == PIOS_USART_DEV_MAGIC); } -#if defined(PIOS_INCLUDE_FREERTOS) && 0 +#if defined(PIOS_INCLUDE_FREERTOS) static struct pios_usart_dev * PIOS_USART_alloc(void) { struct pios_usart_dev * usart_dev; - usart_dev = (struct pios_usart_dev *)malloc(sizeof(*usart_dev)); + usart_dev = (struct pios_usart_dev *)pvPortMalloc(sizeof(*usart_dev)); if (!usart_dev) return(NULL); usart_dev->magic = PIOS_USART_DEV_MAGIC; diff --git a/flight/PiOS/STM32F10x/pios_usb_hid.c b/flight/PiOS/STM32F10x/pios_usb_hid.c index 0ebca1320..8644dd517 100644 --- a/flight/PiOS/STM32F10x/pios_usb_hid.c +++ b/flight/PiOS/STM32F10x/pios_usb_hid.c @@ -75,12 +75,12 @@ static bool PIOS_USB_HID_validate(struct pios_usb_hid_dev * usb_hid_dev) return (usb_hid_dev->magic == PIOS_USB_HID_DEV_MAGIC); } -#if defined(PIOS_INCLUDE_FREERTOS) && 0 +#if defined(PIOS_INCLUDE_FREERTOS) static struct pios_usb_hid_dev * PIOS_USB_HID_alloc(void) { struct pios_usb_hid_dev * usb_hid_dev; - usb_hid_dev = (struct pios_usb_hid_dev *)malloc(sizeof(*usb_hid_dev)); + usb_hid_dev = (struct pios_usb_hid_dev *)pvPortMalloc(sizeof(*usb_hid_dev)); if (!usb_hid_dev) return(NULL); usb_hid_dev->magic = PIOS_USB_HID_DEV_MAGIC; diff --git a/flight/PiOS/STM32F2xx/pios_sys.c b/flight/PiOS/STM32F2xx/pios_sys.c index aafb47571..4ca3bba0c 100644 --- a/flight/PiOS/STM32F2xx/pios_sys.c +++ b/flight/PiOS/STM32F2xx/pios_sys.c @@ -55,9 +55,6 @@ void PIOS_SYS_Init(void) PIOS_DELAY_Init(); PIOS_DELAY_WaitmS(500); /* XXX wait for the OpenOCD DCC stuff to get its act together */ - /* Debug services */ - PIOS_DEBUG_Init(); - /* * Turn on all the peripheral clocks. * Micromanaging clocks makes no sense given the power situation in the system, so diff --git a/flight/PiOS/inc/pios_debug.h b/flight/PiOS/inc/pios_debug.h index e663d224e..4dc5f5b3e 100644 --- a/flight/PiOS/inc/pios_debug.h +++ b/flight/PiOS/inc/pios_debug.h @@ -33,7 +33,9 @@ extern const char *PIOS_DEBUG_AssertMsg; -void PIOS_DEBUG_Init(void); +#include + +void PIOS_DEBUG_Init(const struct pios_tim_channel * channels, uint8_t num_channels); void PIOS_DEBUG_PinHigh(uint8_t pin); void PIOS_DEBUG_PinLow(uint8_t pin); void PIOS_DEBUG_PinValue8Bit(uint8_t value); diff --git a/flight/Modules/GPS/inc/GTOP_BIN.h b/flight/PiOS/inc/pios_gcsrcvr_priv.h similarity index 67% rename from flight/Modules/GPS/inc/GTOP_BIN.h rename to flight/PiOS/inc/pios_gcsrcvr_priv.h index 6a5234430..9a828cb95 100644 --- a/flight/Modules/GPS/inc/GTOP_BIN.h +++ b/flight/PiOS/inc/pios_gcsrcvr_priv.h @@ -1,14 +1,14 @@ /** ****************************************************************************** - * @addtogroup OpenPilotModules OpenPilot Modules + * @addtogroup PIOS PIOS Core hardware abstraction layer * @{ - * @addtogroup GSPModule GPS Module - * @brief Process GPS information + * @addtogroup PIOS_GCSRCVR GCS Receiver Functions + * @brief PIOS interface to read from GCS receiver port * @{ * - * @file GTOP_BIN.h + * @file pios_gcsrcvr_priv.h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief GPS module, handles GPS and NMEA stream + * @brief GCS receiver private functions * @see The GNU Public License (GPL) Version 3 * *****************************************************************************/ @@ -28,15 +28,20 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#ifndef GTOP_BIN_H -#define GTOP_BIN_H +#ifndef PIOS_GCSRCVR_PRIV_H +#define PIOS_GCSRCVR_PRIV_H -#include -#include "gps_mode.h" +#include -#ifdef ENABLE_GPS_BINARY_GTOP - extern int GTOP_BIN_update_position(uint8_t b, volatile uint32_t *chksum_errors, volatile uint32_t *parsing_errors); - extern void GTOP_BIN_init(void); -#endif +#include "gcsreceiver.h" -#endif +extern const struct pios_rcvr_driver pios_gcsrcvr_rcvr_driver; + +extern void PIOS_GCSRCVR_Init(void); + +#endif /* PIOS_GCSRCVR_PRIV_H */ + +/** + * @} + * @} + */ diff --git a/flight/PiOS/inc/pios_ppm_priv.h b/flight/PiOS/inc/pios_ppm_priv.h index fd863fc50..0facab9d5 100644 --- a/flight/PiOS/inc/pios_ppm_priv.h +++ b/flight/PiOS/inc/pios_ppm_priv.h @@ -35,24 +35,14 @@ #include struct pios_ppm_cfg { - TIM_TimeBaseInitTypeDef tim_base_init; TIM_ICInitTypeDef tim_ic_init; - GPIO_InitTypeDef gpio_init; - uint32_t remap; /* GPIO_Remap_* */ - struct stm32_irq irq; - TIM_TypeDef * timer; - GPIO_TypeDef * port; - uint16_t ccr; + const struct pios_tim_channel * channels; + uint8_t num_channels; }; -extern void PIOS_PPM_irq_handler(); - -extern uint8_t pios_ppm_num_channels; -extern const struct pios_ppm_cfg pios_ppm_cfg; - extern const struct pios_rcvr_driver pios_ppm_rcvr_driver; -extern void PIOS_PPM_Init(void); +extern int32_t PIOS_PPM_Init(uint32_t * ppm_id, const struct pios_ppm_cfg * cfg); #endif /* PIOS_PPM_PRIV_H */ diff --git a/flight/PiOS/inc/pios_pwm_priv.h b/flight/PiOS/inc/pios_pwm_priv.h index 23d7d4818..fe11b3d60 100644 --- a/flight/PiOS/inc/pios_pwm_priv.h +++ b/flight/PiOS/inc/pios_pwm_priv.h @@ -34,32 +34,17 @@ #include #include -struct pios_pwm_channel { - TIM_TypeDef * timer; - GPIO_TypeDef * port; - uint16_t ccr; - uint8_t channel; - uint16_t pin; -}; +#include struct pios_pwm_cfg { - TIM_TimeBaseInitTypeDef tim_base_init; TIM_ICInitTypeDef tim_ic_init; - GPIO_InitTypeDef gpio_init; - uint32_t remap; /* GPIO_Remap_* */ - struct stm32_irq irq; - const struct pios_pwm_channel *const channels; + const struct pios_tim_channel * channels; uint8_t num_channels; }; -extern void PIOS_PWM_irq_handler(TIM_TypeDef * timer); - -extern uint8_t pios_pwm_num_channels; -extern const struct pios_pwm_cfg pios_pwm_cfg; - extern const struct pios_rcvr_driver pios_pwm_rcvr_driver; -extern void PIOS_PWM_Init(void); +extern int32_t PIOS_PWM_Init(uint32_t * pwm_id, const struct pios_pwm_cfg * cfg); #endif /* PIOS_PWM_PRIV_H */ diff --git a/flight/PiOS/inc/pios_rcvr.h b/flight/PiOS/inc/pios_rcvr.h index dfec004f5..ab493cd35 100644 --- a/flight/PiOS/inc/pios_rcvr.h +++ b/flight/PiOS/inc/pios_rcvr.h @@ -31,13 +31,6 @@ #ifndef PIOS_RCVR_H #define PIOS_RCVR_H -struct pios_rcvr_channel_map { - uint32_t id; - uint8_t channel; -}; - -extern struct pios_rcvr_channel_map pios_rcvr_channel_to_id_map[]; - struct pios_rcvr_driver { void (*init)(uint32_t id); int32_t (*read)(uint32_t id, uint8_t channel); @@ -46,6 +39,16 @@ struct pios_rcvr_driver { /* Public Functions */ extern int32_t PIOS_RCVR_Read(uint32_t rcvr_id, uint8_t channel); +/*! Define error codes for PIOS_RCVR_Get */ +enum PIOS_RCVR_errors { + /*! Indicates that a failsafe condition or missing receiver detected for that channel */ + PIOS_RCVR_TIMEOUT = 0, + /*! Channel is invalid for this driver (usually out of range supported) */ + PIOS_RCVR_INVALID = -1, + /*! Indicates that the driver for this channel has not been initialized */ + PIOS_RCVR_NODRIVER = -2 +}; + #endif /* PIOS_RCVR_H */ /** diff --git a/flight/PiOS/inc/pios_servo.h b/flight/PiOS/inc/pios_servo.h index 2d621cb25..043d656df 100644 --- a/flight/PiOS/inc/pios_servo.h +++ b/flight/PiOS/inc/pios_servo.h @@ -31,7 +31,6 @@ #define PIOS_SERVO_H /* Public Functions */ -extern void PIOS_Servo_Init(void); extern void PIOS_Servo_SetHz(uint16_t * update_rates, uint8_t channels); extern void PIOS_Servo_Set(uint8_t Servo, uint16_t Position); diff --git a/flight/PiOS/inc/pios_servo_priv.h b/flight/PiOS/inc/pios_servo_priv.h index a1136c46d..f5ed86e25 100644 --- a/flight/PiOS/inc/pios_servo_priv.h +++ b/flight/PiOS/inc/pios_servo_priv.h @@ -33,25 +33,18 @@ #include #include - -struct pios_servo_channel { - TIM_TypeDef * timer; - GPIO_TypeDef * port; - uint8_t channel; - uint16_t pin; -}; +#include struct pios_servo_cfg { TIM_TimeBaseInitTypeDef tim_base_init; TIM_OCInitTypeDef tim_oc_init; GPIO_InitTypeDef gpio_init; uint32_t remap; - const struct pios_servo_channel *const channels; + const struct pios_tim_channel * channels; uint8_t num_channels; }; - -extern const struct pios_servo_cfg pios_servo_cfg; +extern int32_t PIOS_Servo_Init(const struct pios_servo_cfg * cfg); #endif /* PIOS_SERVO_PRIV_H */ diff --git a/flight/PiOS/inc/pios_spektrum_priv.h b/flight/PiOS/inc/pios_spektrum_priv.h index 2d31a8027..17b330cae 100644 --- a/flight/PiOS/inc/pios_spektrum_priv.h +++ b/flight/PiOS/inc/pios_spektrum_priv.h @@ -42,9 +42,9 @@ struct pios_spektrum_cfg { extern const struct pios_rcvr_driver pios_spektrum_rcvr_driver; -extern int32_t PIOS_SPEKTRUM_Init(uint32_t * spektrum_id, const struct pios_spektrum_cfg *cfg, const struct pios_com_driver * driver, uint32_t lower_id, bool bind); +extern int32_t PIOS_SPEKTRUM_Init(uint32_t * spektrum_id, const struct pios_spektrum_cfg *cfg, const struct pios_com_driver * driver, uint32_t lower_id, uint8_t bind); -#endif /* PIOS_PWM_PRIV_H */ +#endif /* PIOS_SPEKTRUM_PRIV_H */ /** * @} diff --git a/flight/PiOS/inc/pios_tim.h b/flight/PiOS/inc/pios_tim.h new file mode 100644 index 000000000..0bad07f41 --- /dev/null +++ b/flight/PiOS/inc/pios_tim.h @@ -0,0 +1,4 @@ +#ifndef PIOS_TIM_H +#define PIOS_TIM_H + +#endif /* PIOS_TIM_H */ diff --git a/flight/PiOS/inc/pios_tim_priv.h b/flight/PiOS/inc/pios_tim_priv.h new file mode 100644 index 000000000..7f05719f8 --- /dev/null +++ b/flight/PiOS/inc/pios_tim_priv.h @@ -0,0 +1,28 @@ +#ifndef PIOS_TIM_PRIV_H +#define PIOS_TIM_PRIV_H + +#include + +struct pios_tim_clock_cfg { + TIM_TypeDef * timer; + const TIM_TimeBaseInitTypeDef * time_base_init; + struct stm32_irq irq; +}; + +struct pios_tim_channel { + TIM_TypeDef * timer; + uint8_t timer_chan; + + struct stm32_gpio pin; + uint32_t remap; +}; + +struct pios_tim_callbacks { + void (*overflow)(uint32_t tim_id, uint32_t context, uint8_t chan_idx, uint16_t count); + void (*edge)(uint32_t tim_id, uint32_t context, uint8_t chan_idx, uint16_t count); +}; + +extern int32_t PIOS_TIM_InitClock(const struct pios_tim_clock_cfg * cfg); +extern 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); + +#endif /* PIOS_TIM_PRIV_H */ diff --git a/flight/Project/OpenPilotOSX/OpenPilotOSX.xcodeproj/project.pbxproj b/flight/Project/OpenPilotOSX/OpenPilotOSX.xcodeproj/project.pbxproj index fdf7c90a3..89d058503 100644 --- a/flight/Project/OpenPilotOSX/OpenPilotOSX.xcodeproj/project.pbxproj +++ b/flight/Project/OpenPilotOSX/OpenPilotOSX.xcodeproj/project.pbxproj @@ -257,6 +257,14 @@ 65632DF71251650300469B77 /* STM3210E_OP.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = STM3210E_OP.h; sourceTree = ""; }; 65643CEC141429A100A32F59 /* NMEA.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = NMEA.c; sourceTree = ""; }; 65643CEE141429AF00A32F59 /* NMEA.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = NMEA.h; sourceTree = ""; }; + 65643CAB1413322000A32F59 /* pios_rcvr_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_rcvr_priv.h; sourceTree = ""; }; + 65643CAC1413322000A32F59 /* pios_rcvr.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_rcvr.h; sourceTree = ""; }; + 65643CAD1413322000A32F59 /* pios_rtc_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_rtc_priv.h; sourceTree = ""; }; + 65643CAE1413322000A32F59 /* pios_sbus_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_sbus_priv.h; sourceTree = ""; }; + 65643CAF1413322000A32F59 /* pios_sbus.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_sbus.h; sourceTree = ""; }; + 65643CB01413322000A32F59 /* pios_spektrum_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_spektrum_priv.h; sourceTree = ""; }; + 65643CB91413456D00A32F59 /* pios_tim.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_tim.c; sourceTree = ""; }; + 65643CBA141350C200A32F59 /* pios_sbus.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_sbus.c; sourceTree = ""; }; 6572CB1613D0F2B200FC2972 /* link_STM32103CB_CC_Rev1_memory.ld */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; name = link_STM32103CB_CC_Rev1_memory.ld; path = ../../PiOS/STM32F10x/link_STM32103CB_CC_Rev1_memory.ld; sourceTree = SOURCE_ROOT; }; 6572CB1713D0F2B200FC2972 /* link_STM32103CB_CC_Rev1_sections.ld */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; name = link_STM32103CB_CC_Rev1_sections.ld; path = ../../PiOS/STM32F10x/link_STM32103CB_CC_Rev1_sections.ld; sourceTree = SOURCE_ROOT; }; 657CEEAD121DB6C8007A1FBE /* homelocation.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = homelocation.xml; sourceTree = ""; }; @@ -8225,11 +8233,17 @@ 65E8F04811EFF25C00BBF654 /* pios_ppm.h */, 65E8F04911EFF25C00BBF654 /* pios_pwm.h */, 657FF86A12EA8BFB00801617 /* pios_pwm_priv.h */, + 65643CAC1413322000A32F59 /* pios_rcvr.h */, + 65643CAB1413322000A32F59 /* pios_rcvr_priv.h */, 6589A9E2131DF1C7006BD67C /* pios_rtc.h */, + 65643CAD1413322000A32F59 /* pios_rtc_priv.h */, + 65643CAE1413322000A32F59 /* pios_sbus_priv.h */, + 65643CAF1413322000A32F59 /* pios_sbus.h */, 65E8F04A11EFF25C00BBF654 /* pios_sdcard.h */, 65E8F04B11EFF25C00BBF654 /* pios_servo.h */, 65FBE14412E7C98100176B5A /* pios_servo_priv.h */, 65E8F04C11EFF25C00BBF654 /* pios_spektrum.h */, + 65643CB01413322000A32F59 /* pios_spektrum_priv.h */, 65E8F04D11EFF25C00BBF654 /* pios_spi.h */, 65E8F04E11EFF25C00BBF654 /* pios_spi_priv.h */, 65E8F04F11EFF25C00BBF654 /* pios_stm32.h */, @@ -8283,10 +8297,12 @@ 65E8F0E411EFF25C00BBF654 /* pios_ppm.c */, 65E8F0E511EFF25C00BBF654 /* pios_pwm.c */, 6589A9DB131DEE76006BD67C /* pios_rtc.c */, + 65643CBA141350C200A32F59 /* pios_sbus.c */, 65E8F0E611EFF25C00BBF654 /* pios_servo.c */, 65E8F0E711EFF25C00BBF654 /* pios_spektrum.c */, 65E8F0E811EFF25C00BBF654 /* pios_spi.c */, 65E8F0E911EFF25C00BBF654 /* pios_sys.c */, + 65643CB91413456D00A32F59 /* pios_tim.c */, 65E8F0EA11EFF25C00BBF654 /* pios_usart.c */, 65E8F0ED11EFF25C00BBF654 /* pios_usb_hid.c */, 651CF9E5120B5D8300EEFD70 /* pios_usb_hid_desc.c */, diff --git a/flight/UAVTalk/inc/uavtalk_priv.h b/flight/UAVTalk/inc/uavtalk_priv.h index 1bcf01fd9..06f08b997 100644 --- a/flight/UAVTalk/inc/uavtalk_priv.h +++ b/flight/UAVTalk/inc/uavtalk_priv.h @@ -51,7 +51,7 @@ typedef struct { typedef uint8_t uavtalk_checksum; #define UAVTALK_CHECKSUM_LENGTH sizeof(uavtalk_checksum) -#define UAVTALK_MAX_PAYLOAD_LENGTH UAVOBJECTS_LARGEST +#define UAVTALK_MAX_PAYLOAD_LENGTH (UAVOBJECTS_LARGEST + 1) #define UAVTALK_MIN_PACKET_LENGTH UAVTALK_MAX_HEADER_LENGTH + UAVTALK_CHECKSUM_LENGTH #define UAVTALK_MAX_PACKET_LENGTH UAVTALK_MIN_PACKET_LENGTH + UAVTALK_MAX_PAYLOAD_LENGTH diff --git a/ground/openpilotgcs/src/libs/utils/cachedsvgitem.cpp b/ground/openpilotgcs/src/libs/utils/cachedsvgitem.cpp new file mode 100644 index 000000000..2edef8ddf --- /dev/null +++ b/ground/openpilotgcs/src/libs/utils/cachedsvgitem.cpp @@ -0,0 +1,159 @@ +/** + ****************************************************************************** + * + * @file cachedsvgitem.h + * @author Dmytro Poplavskiy Copyright (C) 2011. + * @{ + * @brief OpenGL texture cached SVG item + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "cachedsvgitem.h" +#include +#include + +#ifndef GL_CLAMP_TO_EDGE +#define GL_CLAMP_TO_EDGE 0x812F +#endif + +CachedSvgItem::CachedSvgItem(QGraphicsItem * parent) : + QGraphicsSvgItem(parent), + m_context(0), + m_texture(0), + m_scale(1.0) +{ + setCacheMode(NoCache); +} + +CachedSvgItem::CachedSvgItem(const QString & fileName, QGraphicsItem * parent): + QGraphicsSvgItem(fileName, parent), + m_context(0), + m_texture(0), + m_scale(1.0) +{ + setCacheMode(NoCache); +} + +CachedSvgItem::~CachedSvgItem() +{ + if (m_context && m_texture) { + m_context->makeCurrent(); + glDeleteTextures(1, &m_texture); + } +} + +void CachedSvgItem::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget) +{ + + if (painter->paintEngine()->type() != QPaintEngine::OpenGL && + painter->paintEngine()->type() != QPaintEngine::OpenGL2) { + //Fallback to direct painting + QGraphicsSvgItem::paint(painter, option, widget); + return; + } + + QRectF br = boundingRect(); + QTransform transform = painter->worldTransform(); + qreal sceneScale = transform.map(QLineF(0,0,1,0)).length(); + + bool stencilTestEnabled = glIsEnabled(GL_STENCIL_TEST); + bool scissorTestEnabled = glIsEnabled(GL_SCISSOR_TEST); + + painter->beginNativePainting(); + + if (stencilTestEnabled) + glEnable(GL_STENCIL_TEST); + if (scissorTestEnabled) + glEnable(GL_SCISSOR_TEST); + + bool dirty = false; + if (!m_texture) { + glGenTextures(1, &m_texture); + m_context = const_cast(QGLContext::currentContext()); + + dirty = true; + } + + if (!qFuzzyCompare(sceneScale, m_scale)) { + m_scale = sceneScale; + dirty = true; + } + + int textureWidth = (int(br.width()*m_scale) + 3) & ~3; + int textureHeight = (int(br.height()*m_scale) + 3) & ~3; + + if (dirty) { + //qDebug() << "re-render image"; + + QImage img(textureWidth, textureHeight, QImage::Format_ARGB32); + { + img.fill(Qt::transparent); + QPainter p; + p.begin(&img); + p.setRenderHints(painter->renderHints()); + p.translate(br.topLeft()); + p.scale(m_scale, m_scale); + QGraphicsSvgItem::paint(&p, option, 0); + p.end(); + + img = img.rgbSwapped(); + } + + glEnable(GL_TEXTURE_2D); + + glBindTexture(GL_TEXTURE_2D, m_texture); + glTexImage2D( + GL_TEXTURE_2D, + 0, + GL_RGBA, + textureWidth, + textureHeight, + 0, + GL_RGBA, + GL_UNSIGNED_BYTE, + img.bits()); + + glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR); + glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR); + glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE); + glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE); + + glDisable(GL_TEXTURE_2D); + + dirty = false; + } + + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + glEnable(GL_TEXTURE_2D); + + glBindTexture(GL_TEXTURE_2D, m_texture); + + //texture may be slightly large than svn image, ensure only used area is rendered + qreal tw = br.width()*m_scale/textureWidth; + qreal th = br.height()*m_scale/textureHeight; + + glBegin(GL_QUADS); + glTexCoord2d(0, 0 ); glVertex3d(br.left(), br.top(), -1); + glTexCoord2d(tw, 0 ); glVertex3d(br.right(), br.top(), -1); + glTexCoord2d(tw, th); glVertex3d(br.right(), br.bottom(), -1); + glTexCoord2d(0, th); glVertex3d(br.left(), br.bottom(), -1); + glEnd(); + glDisable(GL_TEXTURE_2D); + + painter->endNativePainting(); +} diff --git a/ground/openpilotgcs/src/libs/utils/cachedsvgitem.h b/ground/openpilotgcs/src/libs/utils/cachedsvgitem.h new file mode 100644 index 000000000..747ef391c --- /dev/null +++ b/ground/openpilotgcs/src/libs/utils/cachedsvgitem.h @@ -0,0 +1,54 @@ +/** + ****************************************************************************** + * + * @file cachedsvgitem.h + * @author Dmytro Poplavskiy Copyright (C) 2011. + * @{ + * @brief OpenGL texture cached SVG item + *****************************************************************************/ +/* + * 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 CACHEDSVGITEM_H +#define CACHEDSVGITEM_H + +#include +#include + +#include "utils_global.h" + +class QGLContext; + +//Cache Svg item as GL Texture. +//Texture is regenerated each time item is scaled +//but it's reused during rotation, unlike DeviceCoordinateCache mode +class QTCREATOR_UTILS_EXPORT CachedSvgItem: public QGraphicsSvgItem +{ + Q_OBJECT +public: + CachedSvgItem(QGraphicsItem * parent = 0); + CachedSvgItem(const QString & fileName, QGraphicsItem * parent = 0); + ~CachedSvgItem(); + + void paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget); + +private: + QGLContext *m_context; + GLuint m_texture; + qreal m_scale; +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.cpp b/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.cpp index faf2c911e..c412a475c 100644 --- a/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.cpp +++ b/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.cpp @@ -65,7 +65,7 @@ MyTabbedStackWidget::MyTabbedStackWidget(QWidget *parent, bool isVertical, bool m_stackWidget->setContentsMargins(0, 0, 0, 0); setLayout(toplevelLayout); - connect(m_listWidget, SIGNAL(currentRowChanged(int)), this, SLOT(showWidget(int))); + connect(m_listWidget, SIGNAL(currentRowChanged(int)), this, SLOT(showWidget(int)),Qt::QueuedConnection); } void MyTabbedStackWidget::insertTab(const int index, QWidget *tab, const QIcon &icon, const QString &label) @@ -97,9 +97,19 @@ void MyTabbedStackWidget::setCurrentIndex(int index) void MyTabbedStackWidget::showWidget(int index) { - emit currentAboutToShow(index); - m_stackWidget->setCurrentIndex(index); - emit currentChanged(index); + if(m_stackWidget->currentIndex()==index) + return; + bool proceed=false; + emit currentAboutToShow(index,&proceed); + if(proceed) + { + m_stackWidget->setCurrentIndex(index); + emit currentChanged(index); + } + else + { + m_listWidget->setCurrentRow(m_stackWidget->currentIndex(),QItemSelectionModel::ClearAndSelect); + } } void MyTabbedStackWidget::insertCornerWidget(int index, QWidget *widget) diff --git a/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.h b/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.h index 428ed8646..f32524ce5 100644 --- a/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.h +++ b/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.h @@ -51,9 +51,10 @@ public: void insertCornerWidget(int index, QWidget *widget); int cornerWidgetCount() { return m_cornerWidgetCount; } + QWidget * currentWidget(){return m_stackWidget->currentWidget();} signals: - void currentAboutToShow(int index); + void currentAboutToShow(int index,bool * proceed); void currentChanged(int index); public slots: diff --git a/ground/openpilotgcs/src/libs/utils/utils.pro b/ground/openpilotgcs/src/libs/utils/utils.pro index 804f7c813..003497b4d 100644 --- a/ground/openpilotgcs/src/libs/utils/utils.pro +++ b/ground/openpilotgcs/src/libs/utils/utils.pro @@ -3,7 +3,9 @@ TARGET = Utils QT += gui \ network \ - xml + xml \ + svg \ + opengl DEFINES += QTCREATOR_UTILS_LIB @@ -48,7 +50,8 @@ SOURCES += reloadpromptutils.cpp \ homelocationutil.cpp \ mytabbedstackwidget.cpp \ mytabwidget.cpp \ - mylistwidget.cpp + mylistwidget.cpp \ + cachedsvgitem.cpp SOURCES += xmlconfig.cpp win32 { @@ -102,7 +105,8 @@ HEADERS += utils_global.h \ homelocationutil.h \ mytabbedstackwidget.h \ mytabwidget.h \ - mylistwidget.h + mylistwidget.h \ + cachedsvgitem.h HEADERS += xmlconfig.h FORMS += filewizardpage.ui \ diff --git a/ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui b/ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui index a4a8586e5..2f849e66c 100644 --- a/ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui +++ b/ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui @@ -87,7 +87,7 @@ - Receiver type + RcvrPort Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter @@ -95,7 +95,7 @@ - + diff --git a/ground/openpilotgcs/src/plugins/config/ccpm.ui b/ground/openpilotgcs/src/plugins/config/ccpm.ui index 12d501f60..7730a7a29 100644 --- a/ground/openpilotgcs/src/plugins/config/ccpm.ui +++ b/ground/openpilotgcs/src/plugins/config/ccpm.ui @@ -70,7 +70,7 @@ - 2 + 0 diff --git a/ground/openpilotgcs/src/plugins/config/config.pro b/ground/openpilotgcs/src/plugins/config/config.pro index c1c4b7e0e..29d872ec9 100644 --- a/ground/openpilotgcs/src/plugins/config/config.pro +++ b/ground/openpilotgcs/src/plugins/config/config.pro @@ -38,6 +38,7 @@ HEADERS += configplugin.h \ defaultattitudewidget.h \ smartsavebutton.h \ defaulthwsettingswidget.h \ + inputchannelform.h \ configcamerastabilizationwidget.h SOURCES += configplugin.cpp \ @@ -67,6 +68,7 @@ SOURCES += configplugin.cpp \ defaultattitudewidget.cpp \ smartsavebutton.cpp \ defaulthwsettingswidget.cpp \ + inputchannelform.cpp \ configcamerastabilizationwidget.cpp FORMS += \ @@ -81,6 +83,7 @@ FORMS += \ ccattitude.ui \ defaultattitude.ui \ defaulthwsettings.ui \ + inputchannelform.ui \ camerastabilization.ui RESOURCES += configgadget.qrc diff --git a/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp b/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp index e5adf27f1..1d98874ba 100644 --- a/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp +++ b/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file configtelemetrywidget.h - * @author E. Lafargue & The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup ConfigPlugin Config Plugin @@ -43,7 +43,7 @@ ConfigCCHWWidget::ConfigCCHWWidget(QWidget *parent) : ConfigTaskWidget(parent) addUAVObjectToWidgetRelation("TelemetrySettings","Speed",m_telemetry->telemetrySpeed); addUAVObjectToWidgetRelation("HwSettings","CC_FlexiPort",m_telemetry->cbFlexi); addUAVObjectToWidgetRelation("HwSettings","CC_MainPort",m_telemetry->cbTele); - addUAVObjectToWidgetRelation("ManualControlSettings","InputMode",m_telemetry->receiverType); + addUAVObjectToWidgetRelation("HwSettings","RcvrPort",m_telemetry->cbRcvr); connect(m_telemetry->cchwHelp,SIGNAL(clicked()),this,SLOT(openHelp())); enableControls(false); populateWidgets(); @@ -67,22 +67,6 @@ void ConfigCCHWWidget::widgetsContentsChanged() { m_telemetry->problems->setText("Warning: you have configured the MainPort and the FlexiPort for the same function, this is currently not suported"); } - else if((m_telemetry->cbTele->currentText()=="Spektrum" ||m_telemetry->cbFlexi->currentText()=="Spektrum") && m_telemetry->receiverType->currentText()!="Spektrum") - { - m_telemetry->problems->setText("Warning: you have a port configured as 'Spektrum' however that is not your selected receiver type"); - } - else if(m_telemetry->cbTele->currentText()=="S.Bus" && m_telemetry->receiverType->currentText()!="S.Bus") - { - m_telemetry->problems->setText("Warning: you have a port configured as 'S.Bus' however that is not your selected receiver type"); - } - else if(m_telemetry->cbTele->currentText()!="S.Bus" && m_telemetry->receiverType->currentText()=="S.Bus") - { - m_telemetry->problems->setText("Warning: you have selected 'S.Bus' as your receiver type however you have no port configured for that protocol"); - } - else if((m_telemetry->cbTele->currentText()!="Spektrum" && m_telemetry->cbFlexi->currentText()!="Spektrum") && m_telemetry->receiverType->currentText()=="Spektrum") - { - m_telemetry->problems->setText("Warning: you have selected 'Spektrum' as your receiver type however you have no port configured for that protocol"); - } else { m_telemetry->problems->setText(""); diff --git a/ground/openpilotgcs/src/plugins/config/config_pro_hw_widget.cpp b/ground/openpilotgcs/src/plugins/config/config_pro_hw_widget.cpp index b3f562acd..e19be52ab 100644 --- a/ground/openpilotgcs/src/plugins/config/config_pro_hw_widget.cpp +++ b/ground/openpilotgcs/src/plugins/config/config_pro_hw_widget.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file configtelemetrywidget.h - * @author E. Lafargue & The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup ConfigPlugin Config Plugin diff --git a/ground/openpilotgcs/src/plugins/config/configairframewidget.cpp b/ground/openpilotgcs/src/plugins/config/configairframewidget.cpp index dcf743915..05eb98c4d 100644 --- a/ground/openpilotgcs/src/plugins/config/configairframewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configairframewidget.cpp @@ -92,26 +92,7 @@ ConfigAirframeWidget::ConfigAirframeWidget(QWidget *parent) : ConfigTaskWidget(p m_aircraft->setupUi(this); setupButtons(m_aircraft->saveAircraftToRAM,m_aircraft->saveAircraftToSD); - addWidget(m_aircraft->customMixerTable); - addWidget(m_aircraft->customThrottle2Curve); - addWidget(m_aircraft->customThrottle1Curve); - addWidget(m_aircraft->multiThrottleCurve); - addWidget(m_aircraft->fixedWingThrottle); - addWidget(m_aircraft->fixedWingType); - addWidget(m_aircraft->feedForwardSlider); - addWidget(m_aircraft->accelTime); - addWidget(m_aircraft->decelTime); - addWidget(m_aircraft->maxAccelSlider); - addWidget(m_aircraft->multirotorFrameType); - addWidget(m_aircraft->multiMotor1); - addWidget(m_aircraft->multiMotor2); - addWidget(m_aircraft->multiMotor3); - addWidget(m_aircraft->multiMotor4); - addWidget(m_aircraft->multiMotor5); - addWidget(m_aircraft->multiMotor6); - addWidget(m_aircraft->multiMotor7); - addWidget(m_aircraft->multiMotor8); - addWidget(m_aircraft->triYawChannel); + addUAVObject("SystemSettings"); addUAVObject("MixerSettings"); addUAVObject("ActuatorSettings"); @@ -217,7 +198,7 @@ ConfigAirframeWidget::ConfigAirframeWidget(QWidget *parent) : ConfigTaskWidget(p // Connect the help button connect(m_aircraft->airframeHelp, SIGNAL(clicked()), this, SLOT(openHelp())); - + addToDirtyMonitor(); } ConfigAirframeWidget::~ConfigAirframeWidget() @@ -462,6 +443,7 @@ void ConfigAirframeWidget::updateCustomThrottle2CurveValue(QList list, d */ void ConfigAirframeWidget::refreshWidgetsValues() { + bool dirty=isDirty(); // Get the Airframe type from the system settings: UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("SystemSettings"))); Q_ASSERT(obj); @@ -913,6 +895,7 @@ void ConfigAirframeWidget::refreshWidgetsValues() } updateCustomAirframeUI(); + setDirty(dirty); } /** @@ -921,6 +904,7 @@ void ConfigAirframeWidget::refreshWidgetsValues() */ void ConfigAirframeWidget::setupAirframeUI(QString frameType) { + bool dirty=isDirty(); if (frameType == "FixedWing" || frameType == "Elevator aileron rudder") { // Setup the UI m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Fixed Wing")); @@ -1118,6 +1102,7 @@ void ConfigAirframeWidget::setupAirframeUI(QString frameType) } m_aircraft->quadShape->setSceneRect(quad->boundingRect()); m_aircraft->quadShape->fitInView(quad, Qt::KeepAspectRatio); + setDirty(dirty); } /** @@ -2139,3 +2124,78 @@ void ConfigAirframeWidget::openHelp() QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/Airframe+configuration", QUrl::StrictMode) ); } +void ConfigAirframeWidget::addToDirtyMonitor() +{ + addWidget(m_aircraft->customMixerTable); + addWidget(m_aircraft->customThrottle2Curve); + addWidget(m_aircraft->customThrottle1Curve); + addWidget(m_aircraft->multiThrottleCurve); + addWidget(m_aircraft->fixedWingThrottle); + addWidget(m_aircraft->fixedWingType); + addWidget(m_aircraft->feedForwardSlider); + addWidget(m_aircraft->accelTime); + addWidget(m_aircraft->decelTime); + addWidget(m_aircraft->maxAccelSlider); + addWidget(m_aircraft->multirotorFrameType); + addWidget(m_aircraft->multiMotor1); + addWidget(m_aircraft->multiMotor2); + addWidget(m_aircraft->multiMotor3); + addWidget(m_aircraft->multiMotor4); + addWidget(m_aircraft->multiMotor5); + addWidget(m_aircraft->multiMotor6); + addWidget(m_aircraft->multiMotor7); + addWidget(m_aircraft->multiMotor8); + addWidget(m_aircraft->triYawChannel); + addWidget(m_aircraft->aircraftType); + addWidget(m_aircraft->fwEngineChannel); + addWidget(m_aircraft->fwAileron1Channel); + addWidget(m_aircraft->fwAileron2Channel); + addWidget(m_aircraft->fwElevator1Channel); + addWidget(m_aircraft->fwElevator2Channel); + addWidget(m_aircraft->fwRudder1Channel); + addWidget(m_aircraft->fwRudder2Channel); + addWidget(m_aircraft->elevonSlider1); + addWidget(m_aircraft->elevonSlider2); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmType); + addWidget(m_aircraft->widget_3->m_ccpm->TabObject); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmTailChannel); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmEngineChannel); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmServoWChannel); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmServoXChannel); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmServoYChannel); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmSingleServo); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmServoZChannel); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmAngleW); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmAngleX); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmCorrectionAngle); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmAngleZ); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmAngleY); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmCollectivePassthrough); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmLinkRoll); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmLinkCyclic); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmCollectiveChannel); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmRevoSlider); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmREVOspinBox); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmCollectiveSlider); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmCollectivespinBox); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmCollectiveScale); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmCollectiveScaleBox); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmCyclicScale); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmPitchScale); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmPitchScaleBox); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmRollScale); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmRollScaleBox); + addWidget(m_aircraft->widget_3->m_ccpm->SwashLvlPositionSlider); + addWidget(m_aircraft->widget_3->m_ccpm->SwashLvlPositionSpinBox); + addWidget(m_aircraft->widget_3->m_ccpm->CurveType); + addWidget(m_aircraft->widget_3->m_ccpm->NumCurvePoints); + addWidget(m_aircraft->widget_3->m_ccpm->CurveValue1); + addWidget(m_aircraft->widget_3->m_ccpm->CurveValue2); + addWidget(m_aircraft->widget_3->m_ccpm->CurveValue3); + addWidget(m_aircraft->widget_3->m_ccpm->CurveToGenerate); + addWidget(m_aircraft->widget_3->m_ccpm->CurveSettings); + addWidget(m_aircraft->widget_3->m_ccpm->ThrottleCurve); + addWidget(m_aircraft->widget_3->m_ccpm->PitchCurve); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmAdvancedSettingsTable); +} + diff --git a/ground/openpilotgcs/src/plugins/config/configairframewidget.h b/ground/openpilotgcs/src/plugins/config/configairframewidget.h index 234a114c1..1383350ee 100644 --- a/ground/openpilotgcs/src/plugins/config/configairframewidget.h +++ b/ground/openpilotgcs/src/plugins/config/configairframewidget.h @@ -58,7 +58,7 @@ private: void updateCustomAirframeUI(); bool setupMixer(double mixerFactors[8][3]); void setupMotors(QList motorList); - + void addToDirtyMonitor(); void resetField(UAVObjectField * field); void resetMixer (MixerCurveWidget *mixer, int numElements, double maxvalue); void resetActuators(); diff --git a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp index 51b63fadb..c659180af 100644 --- a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp @@ -40,22 +40,19 @@ ConfigCCAttitudeWidget::ConfigCCAttitudeWidget(QWidget *parent) : { ui->setupUi(this); connect(ui->zeroBias,SIGNAL(clicked()),this,SLOT(startAccelCalibration())); - connect(ui->saveButton,SIGNAL(clicked()),this,SLOT(saveAttitudeSettings())); - connect(ui->applyButton,SIGNAL(clicked()),this,SLOT(applyAttitudeSettings())); - // Make it smart: - connect(parent, SIGNAL(autopilotConnected()),this, SLOT(onAutopilotConnect())); - connect(parent, SIGNAL(autopilotDisconnected()), this, SLOT(onAutopilotDisconnect())); - enableControls(true); - refreshValues(); // The 1st time this panel is instanciated, the autopilot is already connected. - UAVObject * settings = AttitudeSettings::GetInstance(getObjectManager()); - connect(settings,SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshValues())); + setupButtons(ui->applyButton,ui->saveButton); + addUAVObject("AttitudeSettings"); // Connect the help button connect(ui->ccAttitudeHelp, SIGNAL(clicked()), this, SLOT(openHelp())); + addUAVObjectToWidgetRelation("AttitudeSettings","ZeroDuringArming",ui->zeroGyroBiasOnArming); - + addUAVObjectToWidgetRelation("AttitudeSettings","BoardRotation",ui->rollBias,AttitudeSettings::BOARDROTATION_ROLL); + addUAVObjectToWidgetRelation("AttitudeSettings","BoardRotation",ui->pitchBias,AttitudeSettings::BOARDROTATION_PITCH); + addUAVObjectToWidgetRelation("AttitudeSettings","BoardRotation",ui->yawBias,AttitudeSettings::BOARDROTATION_YAW); + addWidget(ui->zeroBias); } ConfigCCAttitudeWidget::~ConfigCCAttitudeWidget() @@ -63,12 +60,6 @@ ConfigCCAttitudeWidget::~ConfigCCAttitudeWidget() delete ui; } -void ConfigCCAttitudeWidget::enableControls(bool enable) -{ - //ui->applyButton->setEnabled(enable); - ui->saveButton->setEnabled(enable); -} - void ConfigCCAttitudeWidget::attitudeRawUpdated(UAVObject * obj) { QMutexLocker locker(&startStop); @@ -130,26 +121,6 @@ void ConfigCCAttitudeWidget::timeout() { } -void ConfigCCAttitudeWidget::applyAttitudeSettings() { - AttitudeSettings::DataFields attitudeSettingsData = AttitudeSettings::GetInstance(getObjectManager())->getData(); - attitudeSettingsData.BoardRotation[AttitudeSettings::BOARDROTATION_ROLL] = ui->rollBias->value(); - attitudeSettingsData.BoardRotation[AttitudeSettings::BOARDROTATION_PITCH] = ui->pitchBias->value(); - attitudeSettingsData.BoardRotation[AttitudeSettings::BOARDROTATION_YAW] = ui->yawBias->value(); - attitudeSettingsData.ZeroDuringArming = ui->zeroGyroBiasOnArming->isChecked() ? AttitudeSettings::ZERODURINGARMING_TRUE : - AttitudeSettings::ZERODURINGARMING_FALSE; - AttitudeSettings::GetInstance(getObjectManager())->setData(attitudeSettingsData); -} - -void ConfigCCAttitudeWidget::refreshValues() { - AttitudeSettings::DataFields attitudeSettingsData = AttitudeSettings::GetInstance(getObjectManager())->getData(); - - ui->rollBias->setValue(attitudeSettingsData.BoardRotation[0]); - ui->pitchBias->setValue(attitudeSettingsData.BoardRotation[1]); - ui->yawBias->setValue(attitudeSettingsData.BoardRotation[2]); - ui->zeroGyroBiasOnArming->setChecked(attitudeSettingsData.ZeroDuringArming == AttitudeSettings::ZERODURINGARMING_TRUE); - -} - void ConfigCCAttitudeWidget::startAccelCalibration() { QMutexLocker locker(&startStop); @@ -184,16 +155,16 @@ void ConfigCCAttitudeWidget::startAccelCalibration() { } -void ConfigCCAttitudeWidget::saveAttitudeSettings() { - applyAttitudeSettings(); - - UAVDataObject * obj = dynamic_cast(getObjectManager()->getObject(QString("AttitudeSettings"))); - saveObjectToSD(obj); -} - void ConfigCCAttitudeWidget::openHelp() { QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/CopterControl+Attitude+Configuration", QUrl::StrictMode) ); } +void ConfigCCAttitudeWidget::enableControls(bool enable) +{ + if(ui->zeroBias) + ui->zeroBias->setEnabled(enable); + ConfigTaskWidget::enableControls(enable); + +} diff --git a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.h b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.h index 27176b22f..09dfdb222 100644 --- a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.h +++ b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.h @@ -50,9 +50,6 @@ private slots: void attitudeRawUpdated(UAVObject * obj); void timeout(); void startAccelCalibration(); - void saveAttitudeSettings(); - void applyAttitudeSettings(); - virtual void refreshValues(); void openHelp(); private: @@ -69,6 +66,7 @@ private: static const int NUM_ACCEL_UPDATES = 60; static const float ACCEL_SCALE = 0.004f * 9.81f; +protected: virtual void enableControls(bool enable); }; diff --git a/ground/openpilotgcs/src/plugins/config/configccpmwidget.cpp b/ground/openpilotgcs/src/plugins/config/configccpmwidget.cpp index e53cbb70c..4a103987a 100644 --- a/ground/openpilotgcs/src/plugins/config/configccpmwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configccpmwidget.cpp @@ -39,6 +39,7 @@ #include "mixersettings.h" #include "systemsettings.h" +#include "actuatorcommand.h" #define Pi 3.14159265358979323846 @@ -70,8 +71,6 @@ ConfigccpmWidget::ConfigccpmWidget(QWidget *parent) : ConfigTaskWidget(parent) m_ccpm->SwashplateImage->setSceneRect(-50,-30,500,500); //m_ccpm->SwashplateImage->scale(.85,.85); - - QSvgRenderer *renderer = new QSvgRenderer(); renderer->load(QString(":/configgadget/images/ccpm_setup.svg")); @@ -132,78 +131,28 @@ ConfigccpmWidget::ConfigccpmWidget(QWidget *parent) : ConfigTaskWidget(parent) SwashLvlSpinBoxes[i] = new QSpinBox(m_ccpm->SwashLvlSwashplateImage); // use QGraphicsView m_ccpm->SwashLvlSwashplateImage->scene()->addWidget(SwashLvlSpinBoxes[i]); - //SwashLvlSpinBoxes[i]->move(i*50+50,20); - //SwashLvlSpinBoxes[i]->resize(40,20); - //SwashLvlSpinBoxes[i]->heightForWidth() - SwashLvlSpinBoxes[i]->setFixedSize(50,20); SwashLvlSpinBoxes[i]->setMaximum(10000); SwashLvlSpinBoxes[i]->setMinimum(0); SwashLvlSpinBoxes[i]->setValue(0); } - -/* - Servos[0] = new QGraphicsSvgItem(); - Servos[0]->setSharedRenderer(renderer); - Servos[0]->setElementId("ServoW"); - m_ccpm->SwashplateImage->scene()->addItem(Servos[0]); - - Servos[1] = new QGraphicsSvgItem(); - Servos[1]->setSharedRenderer(renderer); - Servos[1]->setElementId("ServoX"); - m_ccpm->SwashplateImage->scene()->addItem(Servos[1]); - - Servos[2] = new QGraphicsSvgItem(); - Servos[2]->setSharedRenderer(renderer); - Servos[2]->setElementId("ServoY"); - m_ccpm->SwashplateImage->scene()->addItem(Servos[2]); - - Servos[3] = new QGraphicsSvgItem(); - Servos[3]->setSharedRenderer(renderer); - Servos[3]->setElementId("ServoZ"); - m_ccpm->SwashplateImage->scene()->addItem(Servos[3]); - - - ServosText[0] = new QGraphicsTextItem(); - ServosText[0]->setDefaultTextColor(Qt::red); - ServosText[0]->setPlainText(QString("-")); - ServosText[0]->setFont(serifFont); - m_ccpm->SwashplateImage->scene()->addItem(ServosText[0]); - - ServosText[1] = new QGraphicsTextItem(); - ServosText[1]->setDefaultTextColor(Qt::red); - ServosText[1]->setPlainText(QString("-")); - ServosText[1]->setFont(serifFont); - m_ccpm->SwashplateImage->scene()->addItem(ServosText[1]); - - ServosText[2] = new QGraphicsTextItem(); - ServosText[2]->setDefaultTextColor(Qt::red); - ServosText[2]->setPlainText(QString("-")); - ServosText[2]->setFont(serifFont); - m_ccpm->SwashplateImage->scene()->addItem(ServosText[2]); - - ServosText[3] = new QGraphicsTextItem(); - ServosText[3]->setDefaultTextColor(Qt::red); - ServosText[3]->setPlainText(QString("-")); - ServosText[3]->setFont(serifFont); - m_ccpm->SwashplateImage->scene()->addItem(ServosText[3]); -*/ m_ccpm->PitchCurve->setMin(-1); resetMixer(m_ccpm->PitchCurve, 5); resetMixer(m_ccpm->ThrottleCurve, 5); + MixerSettings * mixerSettings = MixerSettings::GetInstance(getObjectManager()); + Q_ASSERT(mixerSettings); + UAVObjectField * curve2source = mixerSettings->getField("Curve2Source"); + Q_ASSERT(curve2source); - - + m_ccpm->ccpmCollectiveChannel->addItems(curve2source->getOptions()); + m_ccpm->ccpmCollectiveChannel->setCurrentIndex(0); QStringList channels; - channels << "Channel1" << "Channel2" << - "Channel3" << "Channel4" << "Channel5" << "Channel6" << "Channel7" << "Channel8" ; - m_ccpm->ccpmCollectiveChannel->addItems(channels); - m_ccpm->ccpmCollectiveChannel->setCurrentIndex(8); - channels << "None" ; + channels << "Channel1" << "Channel2" << "Channel3" << "Channel4" << + "Channel5" << "Channel6" << "Channel7" << "Channel8" << "None"; m_ccpm->ccpmEngineChannel->addItems(channels); m_ccpm->ccpmEngineChannel->setCurrentIndex(8); m_ccpm->ccpmTailChannel->addItems(channels); @@ -218,17 +167,17 @@ ConfigccpmWidget::ConfigccpmWidget(QWidget *parent) : ConfigTaskWidget(parent) m_ccpm->ccpmServoZChannel->setCurrentIndex(8); QStringList Types; - Types << "CCPM 2 Servo 90º" << "CCPM 3 Servo 90º" << "CCPM 4 Servo 90º" << "CCPM 3 Servo 120º" << "CCPM 3 Servo 140º" << "FP 2 Servo 90º" << "Custom - User Angles" << "Custom - Advanced Settings" ; + Types << QString::fromUtf8("CCPM 2 Servo 90º") << QString::fromUtf8("CCPM 3 Servo 90º") << + QString::fromUtf8("CCPM 4 Servo 90º") << QString::fromUtf8("CCPM 3 Servo 120º") << + QString::fromUtf8("CCPM 3 Servo 140º") << QString::fromUtf8("FP 2 Servo 90º") << + QString::fromUtf8("Custom - User Angles") << QString::fromUtf8("Custom - Advanced Settings"); m_ccpm->ccpmType->addItems(Types); m_ccpm->ccpmType->setCurrentIndex(m_ccpm->ccpmType->count() - 1); requestccpmUpdate(); UpdateCurveSettings(); - //disable changing number of points in curves until UAVObjects have more than 5 m_ccpm->NumCurvePoints->setEnabled(0); - - UpdateType(); @@ -277,8 +226,6 @@ ConfigccpmWidget::ConfigccpmWidget(QWidget *parent) : ConfigTaskWidget(parent) ccpmSwashplateRedraw(); - // connect(parent, SIGNAL(autopilotConnected()),this, SLOT(requestccpmUpdate())); - } ConfigccpmWidget::~ConfigccpmWidget() @@ -292,7 +239,7 @@ void ConfigccpmWidget::UpdateType() QString TypeText; double AdjustmentAngle=0; - UpdatCCPMOptionsFromUI(); + UpdateCCPMOptionsFromUI(); SetUIComponentVisibilities(); TypeInt = m_ccpm->ccpmType->count() - m_ccpm->ccpmType->currentIndex()-1; @@ -332,7 +279,7 @@ void ConfigccpmWidget::UpdateType() NumServosDefined=4; //set values for pre defined heli types - if (TypeText.compare(QString("CCPM 2 Servo 90º"), Qt::CaseInsensitive)==0) + if (TypeText.compare(QString::fromUtf8("CCPM 2 Servo 90º"), Qt::CaseInsensitive)==0) { m_ccpm->ccpmAngleW->setValue(AdjustmentAngle + 0); m_ccpm->ccpmAngleX->setValue(fmod(AdjustmentAngle + 90,360)); @@ -348,7 +295,7 @@ void ConfigccpmWidget::UpdateType() NumServosDefined=2; } - if (TypeText.compare(QString("CCPM 3 Servo 90º"), Qt::CaseInsensitive)==0) + if (TypeText.compare(QString::fromUtf8("CCPM 3 Servo 90º"), Qt::CaseInsensitive)==0) { m_ccpm->ccpmAngleW->setValue(AdjustmentAngle + 0); m_ccpm->ccpmAngleX->setValue(fmod(AdjustmentAngle + 90,360)); @@ -361,7 +308,7 @@ void ConfigccpmWidget::UpdateType() NumServosDefined=3; } - if (TypeText.compare(QString("CCPM 4 Servo 90º"), Qt::CaseInsensitive)==0) + if (TypeText.compare(QString::fromUtf8("CCPM 4 Servo 90º"), Qt::CaseInsensitive)==0) { m_ccpm->ccpmAngleW->setValue(AdjustmentAngle + 0); m_ccpm->ccpmAngleX->setValue(fmod(AdjustmentAngle + 90,360)); @@ -373,7 +320,7 @@ void ConfigccpmWidget::UpdateType() NumServosDefined=4; } - if (TypeText.compare(QString("CCPM 3 Servo 120º"), Qt::CaseInsensitive)==0) + if (TypeText.compare(QString::fromUtf8("CCPM 3 Servo 120º"), Qt::CaseInsensitive)==0) { m_ccpm->ccpmAngleW->setValue(AdjustmentAngle + 0); m_ccpm->ccpmAngleX->setValue(fmod(AdjustmentAngle + 120,360)); @@ -386,7 +333,7 @@ void ConfigccpmWidget::UpdateType() NumServosDefined=3; } - if (TypeText.compare(QString("CCPM 3 Servo 140º"), Qt::CaseInsensitive)==0) + if (TypeText.compare(QString::fromUtf8("CCPM 3 Servo 140º"), Qt::CaseInsensitive)==0) { m_ccpm->ccpmAngleW->setValue(AdjustmentAngle + 0); m_ccpm->ccpmAngleX->setValue(fmod(AdjustmentAngle + 140,360)); @@ -399,7 +346,7 @@ void ConfigccpmWidget::UpdateType() NumServosDefined=3; } - if (TypeText.compare(QString("FP 2 Servo 90º"), Qt::CaseInsensitive)==0) + if (TypeText.compare(QString::fromUtf8("FP 2 Servo 90º"), Qt::CaseInsensitive)==0) { m_ccpm->ccpmAngleW->setValue(AdjustmentAngle + 0); m_ccpm->ccpmAngleX->setValue(fmod(AdjustmentAngle + 90,360)); @@ -505,6 +452,9 @@ void ConfigccpmWidget::UpdateCurveWidgets() void ConfigccpmWidget::updatePitchCurveValue(QList curveValues0,double Value0) { + Q_UNUSED(curveValues0); + Q_UNUSED(Value0); + int NumCurvePoints,i; double CurrentValue; QList internalCurveValues; @@ -526,6 +476,9 @@ void ConfigccpmWidget::updatePitchCurveValue(QList curveValues0,double V void ConfigccpmWidget::updateThrottleCurveValue(QList curveValues0,double Value0) { + Q_UNUSED(curveValues0); + Q_UNUSED(Value0); + int NumCurvePoints,i; double CurrentValue; QList internalCurveValues; @@ -915,14 +868,10 @@ void ConfigccpmWidget::UpdateMixer() bool useCyclic; int i,j,ThisEnable[6]; float CollectiveConstant,PitchConstant,RollConstant,ThisAngle[6]; - //QTableWidgetItem *newItem;// = new QTableWidgetItem(); QString Channel; ccpmChannelCheck(); - //Type = m_ccpm->ccpmType->count() - m_ccpm->ccpmType->currentIndex()-1; - //CollectiveConstant=m_ccpm->ccpmCollectiveSlider->value()/100.0; - //CorrectionAngle=m_ccpm->ccpmCorrectionAngle->value(); - UpdatCCPMOptionsFromUI(); + UpdateCCPMOptionsFromUI(); useCCPM = !(GUIConfigData.heli.ccpmCollectivePassthroughState || !GUIConfigData.heli.ccpmLinkCyclicState); useCyclic = GUIConfigData.heli.ccpmLinkRollState; @@ -978,15 +927,6 @@ void ConfigccpmWidget::UpdateMixer() //go through the user data and update the mixer matrix for (i=0;i<6;i++) { - /* - data.Mixer0Type = 0;//Disabled,Motor,Servo - data.Mixer0Vector[0] = 0;//ThrottleCurve1 - data.Mixer0Vector[1] = 0;//ThrottleCurve2 - data.Mixer0Vector[2] = 0;//Roll - data.Mixer0Vector[3] = 0;//Pitch - data.Mixer0Vector[4] = 0;//Yaw - - */ if ((MixerChannelData[i]<8)&&((ThisEnable[i])||(i<2))) { m_ccpm->ccpmAdvancedSettingsTable->item(i,0)->setText(QString("%1").arg( MixerChannelData[i]+1 )); @@ -1055,7 +995,7 @@ void ConfigccpmWidget::UpdateMixer() } __attribute__((packed)) heliGUISettingsStruct; */ -void ConfigccpmWidget::UpdatCCPMOptionsFromUI() +void ConfigccpmWidget::UpdateCCPMOptionsFromUI() { bool useCCPM; bool useCyclic; @@ -1097,7 +1037,6 @@ void ConfigccpmWidget::UpdatCCPMOptionsFromUI() GUIConfigData.heli.SliderValue1 = m_ccpm->ccpmPitchScale->value(); } GUIConfigData.heli.SliderValue2 = m_ccpm->ccpmRollScale->value(); - //GUIConfigData.heli.RevoSlider = m_ccpm->ccpmREVOScale->value(); //servo assignments GUIConfigData.heli.ServoIndexW = m_ccpm->ccpmServoWChannel->currentIndex(); @@ -1106,7 +1045,7 @@ void ConfigccpmWidget::UpdatCCPMOptionsFromUI() GUIConfigData.heli.ServoIndexZ = m_ccpm->ccpmServoZChannel->currentIndex(); } -void ConfigccpmWidget::UpdatCCPMUIFromOptions() +void ConfigccpmWidget::UpdateCCPMUIFromOptions() { //swashplate config m_ccpm->ccpmType->setCurrentIndex(m_ccpm->ccpmType->count() - (GUIConfigData.heli.SwasplateType +1)); @@ -1134,7 +1073,6 @@ void ConfigccpmWidget::UpdatCCPMUIFromOptions() m_ccpm->ccpmRollScaleBox->setValue(GUIConfigData.heli.SliderValue2); m_ccpm->ccpmCollectiveSlider->setValue(GUIConfigData.heli.SliderValue0); m_ccpm->ccpmCollectivespinBox->setValue(GUIConfigData.heli.SliderValue0); - //m_ccpm->ccpmREVOScale->setValue(GUIConfigData.heli.RevoSlider); //servo assignments m_ccpm->ccpmServoWChannel->setCurrentIndex(GUIConfigData.heli.ServoIndexW); @@ -1147,7 +1085,7 @@ void ConfigccpmWidget::UpdatCCPMUIFromOptions() void ConfigccpmWidget::SetUIComponentVisibilities() { - UpdatCCPMOptionsFromUI(); + UpdateCCPMOptionsFromUI(); //set which sliders are user... m_ccpm->ccpmRevoMixingBox->setVisible(0); @@ -1183,20 +1121,17 @@ void ConfigccpmWidget::requestccpmUpdate() #define MaxAngleError 2 int MixerDataFromHeli[8][5]; quint8 MixerOutputType[8]; - int EngineChannel,TailRotorChannel,ServoChannels[4],ServoAngles[4],SortAngles[4],CalcAngles[4],ServoCurve2[4]; + int EngineChannel,TailRotorChannel,ServoChannels[4],ServoAngles[4],SortAngles[4],ServoCurve2[4]; int NumServos=0; - double Collective=0.0; - double a1,a2; - int HeadRotation,temp; - int isCCPM=0; if (SwashLvlConfigurationInProgress)return; if (updatingToHardware)return; updatingFromHardware=TRUE; - int i,j; + unsigned int i,j; SystemSettings * systemSettings = SystemSettings::GetInstance(getObjectManager()); + Q_ASSERT(systemSettings); SystemSettings::DataFields systemSettingsData = systemSettings->getData(); Q_ASSERT(SystemSettings::GUICONFIGDATA_NUMELEM == @@ -1205,7 +1140,7 @@ void ConfigccpmWidget::requestccpmUpdate() for(i = 0; i < SystemSettings::GUICONFIGDATA_NUMELEM; i++) GUIConfigData.UAVObject[i]=systemSettingsData.GUIConfigData[i]; - UpdatCCPMUIFromOptions(); + UpdateCCPMUIFromOptions(); // Get existing mixer settings MixerSettings * mixerSettings = MixerSettings::GetInstance(getObjectManager()); @@ -1299,7 +1234,7 @@ void ConfigccpmWidget::requestccpmUpdate() } updatingFromHardware=FALSE; - UpdatCCPMUIFromOptions(); + UpdateCCPMUIFromOptions(); ccpmSwashplateUpdate(); } @@ -1310,116 +1245,83 @@ void ConfigccpmWidget::requestccpmUpdate() void ConfigccpmWidget::sendccpmUpdate() { int i,j; - UAVObjectField *field; - UAVDataObject* obj; if (SwashLvlConfigurationInProgress)return; updatingToHardware=TRUE; //ShowDisclaimer(1); + UpdateCCPMOptionsFromUI(); + + // Store the data required to reconstruct + SystemSettings * systemSettings = SystemSettings::GetInstance(getObjectManager()); + Q_ASSERT(systemSettings); + SystemSettings::DataFields systemSettingsData = systemSettings->getData(); + systemSettingsData.GUIConfigData[0] = GUIConfigData.UAVObject[0]; + systemSettingsData.GUIConfigData[1] = GUIConfigData.UAVObject[1]; + systemSettings->setData(systemSettingsData); + systemSettings->updated(); - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager *objManager = pm->getObject(); + MixerSettings * mixerSettings = MixerSettings::GetInstance(getObjectManager()); + Q_ASSERT(mixerSettings); + MixerSettings::DataFields mixerSettingsData = mixerSettings->getData(); - UpdatCCPMOptionsFromUI(); - obj = dynamic_cast(getObjectManager()->getObject(QString("SystemSettings"))); - field = obj->getField(QString("GUIConfigData")); - field->setValue(GUIConfigData.UAVObject[0],0); - field->setValue(GUIConfigData.UAVObject[1],1); - obj->updated(); - + UpdateMixer(); - - obj = dynamic_cast(objManager->getObject(QString("MixerSettings"))); - Q_ASSERT(obj); + // Set up some helper pointers + qint8 * mixers[8] = {mixerSettingsData.Mixer1Vector, + mixerSettingsData.Mixer2Vector, + mixerSettingsData.Mixer3Vector, + mixerSettingsData.Mixer4Vector, + mixerSettingsData.Mixer5Vector, + mixerSettingsData.Mixer6Vector, + mixerSettingsData.Mixer7Vector, + mixerSettingsData.Mixer8Vector + }; - UpdateMixer(); + quint8 * mixerTypes[8] = { + &mixerSettingsData.Mixer1Type, + &mixerSettingsData.Mixer2Type, + &mixerSettingsData.Mixer3Type, + &mixerSettingsData.Mixer4Type, + &mixerSettingsData.Mixer5Type, + &mixerSettingsData.Mixer6Type, + &mixerSettingsData.Mixer7Type, + &mixerSettingsData.Mixer8Type + }; - //clear the output types - for (i=0;i<8;i++) + //go through the user data and update the mixer matrix + for (i=0;i<6;i++) + { + if (MixerChannelData[i]<8) { - field = obj->getField( QString( "Mixer%1Type" ).arg( i+1 )); - //clear the mixer type - field->setValue("Disabled"); + //set the mixer type + *(mixerTypes[MixerChannelData[i]]) = i==0 ? + MixerSettings::MIXER1TYPE_MOTOR : + MixerSettings::MIXER1TYPE_SERVO; + + //config the vector + for (j=0;j<5;j++) + mixers[MixerChannelData[i]][j] = m_ccpm->ccpmAdvancedSettingsTable->item(i,j+1)->text().toInt(); } + } + //get the user data for the curve into the mixer settings + for (i=0;i<5;i++) + mixerSettingsData.ThrottleCurve1[i] = m_ccpm->CurveSettings->item(i, 0)->text().toDouble(); - //go through the user data and update the mixer matrix - for (i=0;i<6;i++) - { - /* - data.Mixer0Type = 0;//Disabled,Motor,Servo - data.Mixer0Vector[0] = 0;//ThrottleCurve1 - data.Mixer0Vector[1] = 0;//ThrottleCurve2 - data.Mixer0Vector[2] = 0;//Roll - data.Mixer0Vector[3] = 0;//Pitch - data.Mixer0Vector[4] = 0;//Yaw - - */ - if (MixerChannelData[i]<8) - { - //select the correct mixer for this config element - field = obj->getField(QString( "Mixer%1Type" ).arg( MixerChannelData[i]+1 )); - //set the mixer type - if (i==0) - { - field->setValue("Motor"); - } - else - { - field->setValue("Servo"); - } - - //select the correct mixer for this config element - field = obj->getField(QString( "Mixer%1Vector" ).arg( MixerChannelData[i]+1 )); - //config the vector - for (j=0;j<5;j++) - { - field->setValue(m_ccpm->ccpmAdvancedSettingsTable->item(i,j+1)->text().toInt(),j); - } - - } - - } - - - //get the user data for the curve into the mixer settings - field = obj->getField(QString("ThrottleCurve1")); - for (i=0;i<5;i++) - { - field->setValue(m_ccpm->CurveSettings->item(i, 0)->text().toDouble(),i); - } - field = obj->getField(QString("ThrottleCurve2")); - for (i=0;i<5;i++) - { - field->setValue(m_ccpm->CurveSettings->item(i, 1)->text().toDouble(),i); - } - - obj->updated(); - - field = obj->getField(QString("Curve2Source")); + for (i=0;i<5;i++) + mixerSettingsData.ThrottleCurve2[i] = m_ccpm->CurveSettings->item(i, 1)->text().toDouble(); //mapping of collective input to curve 2... //MixerSettings.Curve2Source = Throttle,Roll,Pitch,Yaw,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5 //check if we are using throttle or directly from a channel... if (GUIConfigData.heli.ccpmCollectivePassthroughState) - {// input channel - field->setValue("Accessory0"); - obj->updated(); - - obj = dynamic_cast(objManager->getObject(QString("ManualControlSettings"))); - Q_ASSERT(obj); - field = obj->getField(QString("Accessory0")); - field->setValue(tr( "Channel%1" ).arg(GUIConfigData.heli.CollectiveChannel+1)); - - } + mixerSettingsData.Curve2Source = GUIConfigData.heli.CollectiveChannel; else - {// throttle - - field->setValue("Throttle"); - } + mixerSettingsData.Curve2Source = MixerSettings::CURVE2SOURCE_THROTTLE; - obj->updated(); + mixerSettings->setData(mixerSettingsData); + mixerSettings->updated(); updatingToHardware=FALSE; } @@ -1820,7 +1722,6 @@ void ConfigccpmWidget::enableSwashplateLevellingControl(bool state) mdata.gcsTelemetryUpdateMode = UAVObject::UPDATEMODE_ONCHANGE; mdata.gcsTelemetryUpdatePeriod = 100; SwashLvlConfigurationInProgress=1; - connect(qApp, SIGNAL(focusChanged(QWidget*,QWidget*)),this, SLOT(FocusChanged(QWidget*,QWidget*))); m_ccpm->TabObject->setTabEnabled(0,0); m_ccpm->TabObject->setTabEnabled(2,0); m_ccpm->TabObject->setTabEnabled(3,0); @@ -1831,7 +1732,6 @@ void ConfigccpmWidget::enableSwashplateLevellingControl(bool state) mdata = SwashLvlaccInitialData; // Restore metadata SwashLvlConfigurationInProgress=0; - disconnect(qApp, SIGNAL(focusChanged(QWidget*,QWidget*)),this, SLOT(FocusChanged(QWidget*,QWidget*))); m_ccpm->TabObject->setTabEnabled(0,1); m_ccpm->TabObject->setTabEnabled(2,1); m_ccpm->TabObject->setTabEnabled(3,1); @@ -1857,41 +1757,24 @@ void ConfigccpmWidget::setSwashplateLevel(int percent) SwashLvlServoInterlock=1; - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("ActuatorCommand"))); - UAVObjectField * channel = obj->getField("Channel"); + ActuatorCommand * actuatorCommand = ActuatorCommand::GetInstance(getObjectManager()); + ActuatorCommand::DataFields actuatorCommandData = actuatorCommand->getData(); - - - if (level==0) - { - for (i=0;isetValue(newSwashLvlConfiguration.Neutral[i],newSwashLvlConfiguration.ServoChannels[i]); - SwashLvlSpinBoxes[i]->setValue(newSwashLvlConfiguration.Neutral[i]); - } - - } - else if (level>0) - { - for (i=0;i 0) value = (newSwashLvlConfiguration.Max[i] - newSwashLvlConfiguration.Neutral[i])*level + newSwashLvlConfiguration.Neutral[i]; - channel->setValue(value,newSwashLvlConfiguration.ServoChannels[i]); - SwashLvlSpinBoxes[i]->setValue(value); - } - - } - else if (level<0) - { - for (i=0;isetValue(value,newSwashLvlConfiguration.ServoChannels[i]); - SwashLvlSpinBoxes[i]->setValue(value); - } + actuatorCommandData.Channel[newSwashLvlConfiguration.ServoChannels[i]] = value; + SwashLvlSpinBoxes[i]->setValue(value); } - obj->updated(); + + actuatorCommand->setData(actuatorCommandData); + actuatorCommand->updated(); + SwashLvlServoInterlock=0; return; @@ -1900,76 +1783,41 @@ return; void ConfigccpmWidget::SwashLvlSpinBoxChanged(int value) { + Q_UNUSED(value); int i; if (SwashLvlServoInterlock==1)return; - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("ActuatorCommand"))); - UAVObjectField * channel = obj->getField("Channel"); - switch (SwashLvlState) - { - case 0: - break; - case 1: //Neutral levelling - for (i=0;igetData(); + + for (i = 0; i < CCPM_MAX_SWASH_SERVOS; i++) { + value = SwashLvlSpinBoxes[i]->value(); + + switch (SwashLvlState) { - newSwashLvlConfiguration.Neutral[i]=SwashLvlSpinBoxes[i]->value(); - channel->setValue(newSwashLvlConfiguration.Neutral[i],newSwashLvlConfiguration.ServoChannels[i]); + case 1: //Neutral levelling + newSwashLvlConfiguration.Neutral[i]=value; + break; + case 2: //Max levelling + newSwashLvlConfiguration.Max[i] = value; + break; + case 3: //Min levelling + newSwashLvlConfiguration.Min[i]= value; + break; + case 4: //levelling verification + break; + case 5: //levelling complete + break; + default: + break; } - obj->updated(); - break; - case 2: //Max levelling - for (i=0;ivalue(); - channel->setValue(newSwashLvlConfiguration.Max[i],newSwashLvlConfiguration.ServoChannels[i]); - } - obj->updated(); - break; - case 3: //Min levelling - for (i=0;ivalue(); - channel->setValue(newSwashLvlConfiguration.Min[i],newSwashLvlConfiguration.ServoChannels[i]); - } - obj->updated(); - break; - case 4: //levelling verification - break; - case 5: //levelling complete - break; - default: - break; + + actuatorCommandData.Channel[newSwashLvlConfiguration.ServoChannels[i]] = value; } + + + actuatorCommand->setData(actuatorCommandData); + actuatorCommand->updated(); + return; } - - -void ConfigccpmWidget::FocusChanged(QWidget *oldFocus, QWidget *newFocus) -{ - if (SwashLvlConfigurationInProgress!=1) return; - QMessageBox msgBox; - int ret; - msgBox.setText("

Warning!!!

"); - - if ((this->isAncestorOf(oldFocus))&&(!this->isAncestorOf(newFocus))) - { - msgBox.setInformativeText("You are in the middle of the levelling routine
Changing focus will cancel all levelling and return the OP hardware to the state it was in before levelling began.

Do you want to continue the levelling routine?"); - msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::No); - msgBox.setDefaultButton(QMessageBox::Yes); - msgBox.setIcon(QMessageBox::Information); - ret = msgBox.exec(); - - if (ret == QMessageBox::Yes) - { - - //m_ccpm->TabObject->setCurrentIndex(1); - //m_ccpm->SwashPlateLevel->setFocus(Qt::MouseFocusReason); - //m_ccpm->SwashLvlInstructionsBox->setFocus(Qt::MouseFocusReason); - oldFocus->setFocus(Qt::MouseFocusReason); - } - if (ret == QMessageBox::No) - { - SwashLvlCancelButtonPressed(); - } - } -} diff --git a/ground/openpilotgcs/src/plugins/config/configccpmwidget.h b/ground/openpilotgcs/src/plugins/config/configccpmwidget.h index d07da53c8..56898f0fb 100644 --- a/ground/openpilotgcs/src/plugins/config/configccpmwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configccpmwidget.h @@ -82,6 +82,8 @@ public: ConfigccpmWidget(QWidget *parent = 0); ~ConfigccpmWidget(); + friend class ConfigAirframeWidget; + private: Ui_ccpmWidget *m_ccpm; QGraphicsSvgItem *SwashplateImg; @@ -134,8 +136,8 @@ private: void SwashLvlCancelButtonPressed(); void SwashLvlFinishButtonPressed(); - void UpdatCCPMOptionsFromUI(); - void UpdatCCPMUIFromOptions(); + void UpdateCCPMOptionsFromUI(); + void UpdateCCPMUIFromOptions(); void SetUIComponentVisibilities(); void ccpmChannelCheck(); @@ -143,8 +145,6 @@ private: void enableSwashplateLevellingControl(bool state); void setSwashplateLevel(int percent); void SwashLvlSpinBoxChanged(int value); - void FocusChanged(QWidget *oldFocus, QWidget *newFocus); - virtual void refreshValues() {}; // Not used public slots: diff --git a/ground/openpilotgcs/src/plugins/config/configgadget.qrc b/ground/openpilotgcs/src/plugins/config/configgadget.qrc index 473063c48..f24cb68b8 100644 --- a/ground/openpilotgcs/src/plugins/config/configgadget.qrc +++ b/ground/openpilotgcs/src/plugins/config/configgadget.qrc @@ -15,6 +15,7 @@ images/coptercontrol.svg images/hw_config.png images/gyroscope.png + images/TX.svg images/camera.png diff --git a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp index 426d6e646..a8509d091 100644 --- a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp @@ -102,6 +102,8 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent) onAutopilotConnect(); help = 0; + connect(ftw,SIGNAL(currentAboutToShow(int,bool*)),this,SLOT(tabAboutToChange(int,bool*)));//,Qt::BlockingQueuedConnection); + } ConfigGadgetWidget::~ConfigGadgetWidget() @@ -118,6 +120,15 @@ void ConfigGadgetWidget::resizeEvent(QResizeEvent *event) } void ConfigGadgetWidget::onAutopilotDisconnect() { + ftw->setCurrentIndex(ConfigGadgetWidget::hardware); + ftw->removeTab(ConfigGadgetWidget::ins); + QWidget *qwd = new DefaultAttitudeWidget(this); + ftw->insertTab(ConfigGadgetWidget::ins, qwd, QIcon(":/configgadget/images/AHRS-v1.3.png"), QString("INS")); + ftw->removeTab(ConfigGadgetWidget::hardware); + qwd = new DefaultHwSettingsWidget(this); + ftw->insertTab(ConfigGadgetWidget::hardware, qwd, QIcon(":/configgadget/images/hw_config.png"), QString("HW Settings")); + ftw->setCurrentIndex(ConfigGadgetWidget::hardware); + emit autopilotDisconnected(); } @@ -156,5 +167,23 @@ void ConfigGadgetWidget::onAutopilotConnect() { emit autopilotConnected(); } +void ConfigGadgetWidget::tabAboutToChange(int i,bool * proceed) +{ + *proceed=true; + ConfigTaskWidget * wid=qobject_cast(ftw->currentWidget()); + if(!wid) + return; + if(wid->isDirty()) + { + int ans=QMessageBox::warning(this,tr("Unsaved changes"),tr("The tab you are leaving has unsaved changes," + "if you proceed they will be lost." + "Do you still want to proceed?"),QMessageBox::Yes,QMessageBox::No); + if(ans==QMessageBox::No) + *proceed=false; + else + wid->setDirty(false); + } +} + diff --git a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.h b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.h index 6cfa6e20d..633253507 100644 --- a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.h @@ -37,10 +37,10 @@ //#include #include #include "utils/pathutils.h" - +#include //#include "fancytabwidget.h" #include "utils/mytabbedstackwidget.h" - +#include "configtaskwidget.h" class ConfigGadgetWidget: public QWidget { @@ -55,6 +55,7 @@ public: public slots: void onAutopilotConnect(); void onAutopilotDisconnect(); + void tabAboutToChange(int i,bool *); signals: void autopilotConnected(); diff --git a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp index 83e1a02ac..1590f52f0 100644 --- a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp @@ -1,8 +1,8 @@ /** ****************************************************************************** * - * @file configservowidget.cpp - * @author E. Lafargue & The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @file configinputwidget.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup ConfigPlugin Config Plugin @@ -38,556 +38,923 @@ #include #include #include +#include +#include -#include "manualcontrolsettings.h" +#define ACCESS_MIN_MOVE -6 +#define ACCESS_MAX_MOVE 6 +#define STICK_MIN_MOVE -8 +#define STICK_MAX_MOVE 8 -ConfigInputWidget::ConfigInputWidget(QWidget *parent) : ConfigTaskWidget(parent) +ConfigInputWidget::ConfigInputWidget(QWidget *parent) : ConfigTaskWidget(parent),wizardStep(wizardWelcome),loop(NULL),skipflag(false),goWizard(NULL) { + manualCommandObj = ManualControlCommand::GetInstance(getObjectManager()); + manualSettingsObj = ManualControlSettings::GetInstance(getObjectManager()); + receiverActivityObj=ReceiverActivity::GetInstance(getObjectManager()); m_config = new Ui_InputWidget(); m_config->setupUi(this); - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager *objManager = pm->getObject(); + setupButtons(m_config->saveRCInputToRAM,m_config->saveRCInputToSD); - // First of all, put all the channel widgets into lists, so that we can - // manipulate those: - - - inMaxLabels << m_config->ch0Max - << m_config->ch1Max - << m_config->ch2Max - << m_config->ch3Max - << m_config->ch4Max - << m_config->ch5Max - << m_config->ch6Max - << m_config->ch7Max; - - inMinLabels << m_config->ch0Min - << m_config->ch1Min - << m_config->ch2Min - << m_config->ch3Min - << m_config->ch4Min - << m_config->ch5Min - << m_config->ch6Min - << m_config->ch7Min; - - inSliders << m_config->inSlider0 - << m_config->inSlider1 - << m_config->inSlider2 - << m_config->inSlider3 - << m_config->inSlider4 - << m_config->inSlider5 - << m_config->inSlider6 - << m_config->inSlider7; - - inRevCheckboxes << m_config->ch0Rev - << m_config->ch1Rev - << m_config->ch2Rev - << m_config->ch3Rev - << m_config->ch4Rev - << m_config->ch5Rev - << m_config->ch6Rev - << m_config->ch7Rev; - - inChannelAssign << m_config->ch0Assign - << m_config->ch1Assign - << m_config->ch2Assign - << m_config->ch3Assign - << m_config->ch4Assign - << m_config->ch5Assign - << m_config->ch6Assign - << m_config->ch7Assign; - - // Now connect the widget to the ManualControlCommand / Channel UAVObject - UAVDataObject* obj = dynamic_cast(objManager->getObject(QString("ManualControlCommand"))); - connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(updateChannels(UAVObject*))); - - // Register for ManualControlSettings changes: - obj = dynamic_cast(objManager->getObject(QString("ManualControlSettings"))); - connect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(refreshValues())); - - - // Get the receiver types supported by OpenPilot and fill the corresponding - // dropdown menu: - obj = dynamic_cast(objManager->getObject(QString("ManualControlSettings"))); - UAVObjectField * field; - // Fill in the dropdown menus for the channel RC Input assignement. - QStringList channelsList; - channelsList << "None"; - QList fieldList = obj->getFields(); - foreach (UAVObjectField* field, fieldList) { - if (field->getUnits().contains("channel")) { - channelsList.append(field->getName()); - } + int index=0; + foreach(QString name,manualSettingsObj->getFields().at(0)->getElementNames()) + { + inputChannelForm * inp=new inputChannelForm(this,index==0); + m_config->advancedPage->layout()->addWidget(inp); + inp->ui->channelName->setText(name); + addUAVObjectToWidgetRelation("ManualControlSettings","ChannelGroups",inp->ui->channelGroup,index); + addUAVObjectToWidgetRelation("ManualControlSettings","ChannelNumber",inp->ui->channelNumber,index); + addUAVObjectToWidgetRelation("ManualControlSettings","ChannelMin",inp->ui->channelMin,index); + addUAVObjectToWidgetRelation("ManualControlSettings","ChannelNeutral",inp->ui->channelNeutral,index); + addUAVObjectToWidgetRelation("ManualControlSettings","ChannelMax",inp->ui->channelMax,index); + ++index; } + goWizard=new QPushButton(tr("Start Wizard"),this); + m_config->advancedPage->layout()->addWidget(goWizard); + connect(goWizard,SIGNAL(clicked()),this,SLOT(goToNormalWizard())); + goSimpleWizard=new QPushButton(tr("Start Simple Wizard"),this); + m_config->advancedPage->layout()->addWidget(goSimpleWizard); + connect(goSimpleWizard,SIGNAL(clicked()),this,SLOT(goToSimpleWizard())); - m_config->ch0Assign->addItems(channelsList); - m_config->ch1Assign->addItems(channelsList); - m_config->ch2Assign->addItems(channelsList); - m_config->ch3Assign->addItems(channelsList); - m_config->ch4Assign->addItems(channelsList); - m_config->ch5Assign->addItems(channelsList); - m_config->ch6Assign->addItems(channelsList); - m_config->ch7Assign->addItems(channelsList); + connect(m_config->wzNext,SIGNAL(clicked()),this,SLOT(wzNext())); + connect(m_config->wzCancel,SIGNAL(clicked()),this,SLOT(wzCancel())); + connect(m_config->wzBack,SIGNAL(clicked()),this,SLOT(wzBack())); - // And the flight mode settings: - field = obj->getField(QString("FlightModePosition")); - m_config->fmsModePos1->addItems(field->getOptions()); - m_config->fmsModePos2->addItems(field->getOptions()); - m_config->fmsModePos3->addItems(field->getOptions()); - field = obj->getField(QString("Stabilization1Settings")); - channelsList.clear(); - channelsList.append(field->getOptions()); - m_config->fmsSsPos1Roll->addItems(channelsList); - m_config->fmsSsPos1Pitch->addItems(channelsList); - m_config->fmsSsPos1Yaw->addItems(channelsList); - m_config->fmsSsPos2Roll->addItems(channelsList); - m_config->fmsSsPos2Pitch->addItems(channelsList); - m_config->fmsSsPos2Yaw->addItems(channelsList); - m_config->fmsSsPos3Roll->addItems(channelsList); - m_config->fmsSsPos3Pitch->addItems(channelsList); - m_config->fmsSsPos3Yaw->addItems(channelsList); + m_config->stackedWidget->setCurrentIndex(0); + addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos1,0); + addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos2,1); + addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos3,2); - // And the Armin configurations: - field = obj->getField(QString("Arming")); - m_config->armControl->clear(); - m_config->armControl->addItems(field->getOptions()); - - - connect(m_config->saveRCInputToSD, SIGNAL(clicked()), this, SLOT(saveRCInputObject())); - connect(m_config->saveRCInputToRAM, SIGNAL(clicked()), this, SLOT(sendRCInputUpdate())); + addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization1Settings",m_config->fmsSsPos1Roll,"Roll"); + addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization2Settings",m_config->fmsSsPos2Roll,"Roll"); + addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization3Settings",m_config->fmsSsPos3Roll,"Roll"); + addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization1Settings",m_config->fmsSsPos1Pitch,"Pitch"); + addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization2Settings",m_config->fmsSsPos2Pitch,"Pitch"); + addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization3Settings",m_config->fmsSsPos3Pitch,"Pitch"); + addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization1Settings",m_config->fmsSsPos1Yaw,"Yaw"); + addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization2Settings",m_config->fmsSsPos2Yaw,"Yaw"); + addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization3Settings",m_config->fmsSsPos3Yaw,"Yaw"); + addUAVObjectToWidgetRelation("ManualControlSettings","Arming",m_config->armControl); + addUAVObjectToWidgetRelation("ManualControlSettings","ArmedTimeout",m_config->armTimeout,0,1000); + connect( ManualControlCommand::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(moveFMSlider())); + addWidget(goWizard); + addWidget(goSimpleWizard); enableControls(false); - refreshValues(); - connect(parent, SIGNAL(autopilotConnected()),this, SLOT(onAutopilotConnect())); - connect(parent, SIGNAL(autopilotDisconnected()), this, SLOT(onAutopilotDisconnect())); - - connect(m_config->ch0Rev, SIGNAL(toggled(bool)), this, SLOT(reverseCheckboxClicked(bool))); - connect(m_config->ch1Rev, SIGNAL(toggled(bool)), this, SLOT(reverseCheckboxClicked(bool))); - connect(m_config->ch2Rev, SIGNAL(toggled(bool)), this, SLOT(reverseCheckboxClicked(bool))); - connect(m_config->ch3Rev, SIGNAL(toggled(bool)), this, SLOT(reverseCheckboxClicked(bool))); - connect(m_config->ch4Rev, SIGNAL(toggled(bool)), this, SLOT(reverseCheckboxClicked(bool))); - connect(m_config->ch5Rev, SIGNAL(toggled(bool)), this, SLOT(reverseCheckboxClicked(bool))); - connect(m_config->ch6Rev, SIGNAL(toggled(bool)), this, SLOT(reverseCheckboxClicked(bool))); - connect(m_config->ch7Rev, SIGNAL(toggled(bool)), this, SLOT(reverseCheckboxClicked(bool))); - connect(m_config->doRCInputCalibration,SIGNAL(stateChanged(int)),this,SLOT(updateTips(int))); - firstUpdate = true; + populateWidgets(); + refreshWidgetsValues(); // Connect the help button connect(m_config->inputHelp, SIGNAL(clicked()), this, SLOT(openHelp())); - updateTips(Qt::Unchecked); + m_config->graphicsView->setScene(new QGraphicsScene(this)); + m_config->graphicsView->setViewportUpdateMode(QGraphicsView::FullViewportUpdate); + m_renderer = new QSvgRenderer(); + QGraphicsScene *l_scene = m_config->graphicsView->scene(); + m_config->graphicsView->setBackgroundBrush(QBrush(Utils::StyleHelper::baseColor())); + if (QFile::exists(":/configgadget/images/TX.svg") && m_renderer->load(QString(":/configgadget/images/TX.svg")) && m_renderer->isValid()) + { + l_scene->clear(); // Deletes all items contained in the scene as well. + + m_txBackground = new QGraphicsSvgItem(); + // All other items will be clipped to the shape of the background + m_txBackground->setFlags(QGraphicsItem::ItemClipsChildrenToShape| + QGraphicsItem::ItemClipsToShape); + m_txBackground->setSharedRenderer(m_renderer); + m_txBackground->setElementId("background"); + l_scene->addItem(m_txBackground); + + m_txMainBody = new QGraphicsSvgItem(); + m_txMainBody->setParentItem(m_txBackground); + m_txMainBody->setSharedRenderer(m_renderer); + m_txMainBody->setElementId("body"); + l_scene->addItem(m_txMainBody); + + m_txLeftStick = new QGraphicsSvgItem(); + m_txLeftStick->setParentItem(m_txBackground); + m_txLeftStick->setSharedRenderer(m_renderer); + m_txLeftStick->setElementId("ljoy"); + + m_txRightStick = new QGraphicsSvgItem(); + m_txRightStick->setParentItem(m_txBackground); + m_txRightStick->setSharedRenderer(m_renderer); + m_txRightStick->setElementId("rjoy"); + + m_txAccess0 = new QGraphicsSvgItem(); + m_txAccess0->setParentItem(m_txBackground); + m_txAccess0->setSharedRenderer(m_renderer); + m_txAccess0->setElementId("access0"); + + m_txAccess1 = new QGraphicsSvgItem(); + m_txAccess1->setParentItem(m_txBackground); + m_txAccess1->setSharedRenderer(m_renderer); + m_txAccess1->setElementId("access1"); + + m_txAccess2 = new QGraphicsSvgItem(); + m_txAccess2->setParentItem(m_txBackground); + m_txAccess2->setSharedRenderer(m_renderer); + m_txAccess2->setElementId("access2"); + + m_txFlightMode = new QGraphicsSvgItem(); + m_txFlightMode->setParentItem(m_txBackground); + m_txFlightMode->setSharedRenderer(m_renderer); + m_txFlightMode->setElementId("flightModeCenter"); + m_txFlightMode->setZValue(-10); + + m_txArrows = new QGraphicsSvgItem(); + m_txArrows->setParentItem(m_txBackground); + m_txArrows->setSharedRenderer(m_renderer); + m_txArrows->setElementId("arrows"); + m_txArrows->setVisible(false); + + QRectF orig=m_renderer->boundsOnElement("ljoy"); + QMatrix Matrix = m_renderer->matrixForElement("ljoy"); + orig=Matrix.mapRect(orig); + m_txLeftStickOrig.translate(orig.x(),orig.y()); + m_txLeftStick->setTransform(m_txLeftStickOrig,false); + + orig=m_renderer->boundsOnElement("arrows"); + Matrix = m_renderer->matrixForElement("arrows"); + orig=Matrix.mapRect(orig); + m_txArrowsOrig.translate(orig.x(),orig.y()); + m_txArrows->setTransform(m_txArrowsOrig,false); + + orig=m_renderer->boundsOnElement("body"); + Matrix = m_renderer->matrixForElement("body"); + orig=Matrix.mapRect(orig); + m_txMainBodyOrig.translate(orig.x(),orig.y()); + m_txMainBody->setTransform(m_txMainBodyOrig,false); + + orig=m_renderer->boundsOnElement("flightModeCenter"); + Matrix = m_renderer->matrixForElement("flightModeCenter"); + orig=Matrix.mapRect(orig); + m_txFlightModeCOrig.translate(orig.x(),orig.y()); + m_txFlightMode->setTransform(m_txFlightModeCOrig,false); + + orig=m_renderer->boundsOnElement("flightModeLeft"); + Matrix = m_renderer->matrixForElement("flightModeLeft"); + orig=Matrix.mapRect(orig); + m_txFlightModeLOrig.translate(orig.x(),orig.y()); + orig=m_renderer->boundsOnElement("flightModeRight"); + Matrix = m_renderer->matrixForElement("flightModeRight"); + orig=Matrix.mapRect(orig); + m_txFlightModeROrig.translate(orig.x(),orig.y()); + + orig=m_renderer->boundsOnElement("rjoy"); + Matrix = m_renderer->matrixForElement("rjoy"); + orig=Matrix.mapRect(orig); + m_txRightStickOrig.translate(orig.x(),orig.y()); + m_txRightStick->setTransform(m_txRightStickOrig,false); + + orig=m_renderer->boundsOnElement("access0"); + Matrix = m_renderer->matrixForElement("access0"); + orig=Matrix.mapRect(orig); + m_txAccess0Orig.translate(orig.x(),orig.y()); + m_txAccess0->setTransform(m_txAccess0Orig,false); + + orig=m_renderer->boundsOnElement("access1"); + Matrix = m_renderer->matrixForElement("access1"); + orig=Matrix.mapRect(orig); + m_txAccess1Orig.translate(orig.x(),orig.y()); + m_txAccess1->setTransform(m_txAccess1Orig,false); + + orig=m_renderer->boundsOnElement("access2"); + Matrix = m_renderer->matrixForElement("access2"); + orig=Matrix.mapRect(orig); + m_txAccess2Orig.translate(orig.x(),orig.y()); + m_txAccess2->setTransform(m_txAccess2Orig,true); + } + m_config->graphicsView->fitInView(m_txMainBody, Qt::KeepAspectRatio ); + animate=new QTimer(this); + connect(animate,SIGNAL(timeout()),this,SLOT(moveTxControls())); +} +void ConfigInputWidget::resetTxControls() +{ + + m_txLeftStick->setTransform(m_txLeftStickOrig,false); + m_txRightStick->setTransform(m_txRightStickOrig,false); + m_txAccess0->setTransform(m_txAccess0Orig,false); + m_txAccess1->setTransform(m_txAccess1Orig,false); + m_txAccess2->setTransform(m_txAccess2Orig,false); + m_txFlightMode->setElementId("flightModeCenter"); + m_txFlightMode->setTransform(m_txFlightModeCOrig,false); + m_txArrows->setVisible(false); } ConfigInputWidget::~ConfigInputWidget() { - // Do nothing -} - -/** - Slot called whenever we revert a signal - */ -void ConfigInputWidget::reverseCheckboxClicked(bool state) -{ - QObject* obj = sender(); - int i = inRevCheckboxes.indexOf((QCheckBox*)obj); - - inSliders[i]->setInvertedAppearance(state); - int max = inMaxLabels[i]->text().toInt(); - int min = inMinLabels[i]->text().toInt(); - if ((state && (max>min)) || - (!state && (max < min))) { - inMaxLabels[i]->setText(QString::number(min)); - inMinLabels[i]->setText(QString::number(max)); - } -} - - -// ************************************ - -/* - Enable or disable some controls depending on whether we are connected - or not to the board. Actually, this i mostly useless IMHO, I don't - know who added this into the code (Ed's note) - */ -void ConfigInputWidget::enableControls(bool enable) -{ - //m_config->saveRCInputToRAM->setEnabled(enable); - m_config->saveRCInputToSD->setEnabled(enable); - m_config->doRCInputCalibration->setEnabled(enable); -} - - -/******************************** - * Input settings - *******************************/ - -/** - Request the current config from the board - */ -void ConfigInputWidget::refreshValues() -{ - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("ManualControlSettings"))); - Q_ASSERT(obj); - //obj->requestUpdate(); - UAVObjectField *field; - - // Now update all the slider values: - - UAVObjectField *field_max = obj->getField(QString("ChannelMax")); - UAVObjectField *field_min = obj->getField(QString("ChannelMin")); - UAVObjectField *field_neu = obj->getField(QString("ChannelNeutral")); - Q_ASSERT(field_max); - Q_ASSERT(field_min); - Q_ASSERT(field_neu); - for (int i = 0; i < 8; i++) { - QVariant max = field_max->getValue(i); - QVariant min = field_min->getValue(i); - QVariant neutral = field_neu->getValue(i); - inMaxLabels[i]->setText(max.toString()); - inMinLabels[i]->setText(min.toString()); - if (max.toInt()> min.toInt()) { - inRevCheckboxes[i]->setChecked(false); - inSliders[i]->setMaximum(max.toInt()); - inSliders[i]->setMinimum(min.toInt()); - } else { - inRevCheckboxes[i]->setChecked(true); - inSliders[i]->setMaximum(min.toInt()); - inSliders[i]->setMinimum(max.toInt()); - } - inSliders[i]->setValue(neutral.toInt()); - } - - // Update receiver type - field = obj->getField(QString("InputMode")); - m_config->receiverType->setText(field->getValue().toString()); - - // Reset all channel assignement dropdowns: - foreach (QComboBox *combo, inChannelAssign) { - combo->setCurrentIndex(0); - } - - // Update all channels assignements - QList fieldList = obj->getFields(); - foreach (UAVObjectField *field, fieldList) { - if (field->getUnits().contains("channel")) - assignChannel(obj, field->getName()); - } - - // Update all the flight mode settingsin the relevant tab - field = obj->getField(QString("FlightModePosition")); - m_config->fmsModePos1->setCurrentIndex((m_config->fmsModePos1->findText(field->getValue(0).toString()))); - m_config->fmsModePos2->setCurrentIndex((m_config->fmsModePos2->findText(field->getValue(1).toString()))); - m_config->fmsModePos3->setCurrentIndex((m_config->fmsModePos3->findText(field->getValue(2).toString()))); - - field = obj->getField(QString("Stabilization1Settings")); - m_config->fmsSsPos1Roll->setCurrentIndex(m_config->fmsSsPos1Roll->findText(field->getValue(field->getElementNames().indexOf("Roll")).toString())); - m_config->fmsSsPos1Pitch->setCurrentIndex(m_config->fmsSsPos1Pitch->findText(field->getValue(field->getElementNames().indexOf("Pitch")).toString())); - m_config->fmsSsPos1Yaw->setCurrentIndex(m_config->fmsSsPos1Yaw->findText(field->getValue(field->getElementNames().indexOf("Yaw")).toString())); - field = obj->getField(QString("Stabilization2Settings")); - m_config->fmsSsPos2Roll->setCurrentIndex(m_config->fmsSsPos2Roll->findText(field->getValue(field->getElementNames().indexOf("Roll")).toString())); - m_config->fmsSsPos2Pitch->setCurrentIndex(m_config->fmsSsPos2Pitch->findText(field->getValue(field->getElementNames().indexOf("Pitch")).toString())); - m_config->fmsSsPos2Yaw->setCurrentIndex(m_config->fmsSsPos2Yaw->findText(field->getValue(field->getElementNames().indexOf("Yaw")).toString())); - field = obj->getField(QString("Stabilization3Settings")); - m_config->fmsSsPos3Roll->setCurrentIndex(m_config->fmsSsPos3Roll->findText(field->getValue(field->getElementNames().indexOf("Roll")).toString())); - m_config->fmsSsPos3Pitch->setCurrentIndex(m_config->fmsSsPos3Pitch->findText(field->getValue(field->getElementNames().indexOf("Pitch")).toString())); - m_config->fmsSsPos3Yaw->setCurrentIndex(m_config->fmsSsPos3Yaw->findText(field->getValue(field->getElementNames().indexOf("Yaw")).toString())); - - // Load the arming settings - field = obj->getField(QString("Arming")); - m_config->armControl->setCurrentIndex(m_config->armControl->findText(field->getValue().toString())); - field = obj->getField(QString("ArmedTimeout")); - m_config->armTimeout->setValue(field->getValue().toInt()/1000); -} - - -/** - * Sends the config to the board, without saving to the SD card - */ -void ConfigInputWidget::sendRCInputUpdate() -{ - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager *objManager = pm->getObject(); - UAVDataObject* obj = dynamic_cast(objManager->getObject(QString("ManualControlSettings"))); - Q_ASSERT(obj); - // Now update all fields from the sliders: - QString fieldName = QString("ChannelMax"); - UAVObjectField * field = obj->getField(fieldName); - for (int i = 0; i < 8; i++) { - field->setValue(inMaxLabels[i]->text().toInt(), i); - } - - fieldName = QString("ChannelMin"); - field = obj->getField(fieldName); - for (int i = 0; i < 8; i++) { - field->setValue(inMinLabels[i]->text().toInt(), i); - } - - fieldName = QString("ChannelNeutral"); - field = obj->getField(fieldName); - for (int i = 0; i < 8; i++) - field->setValue(inSliders[i]->value(), i); - - // Set Roll/Pitch/Yaw/Etc assignement: - // Rule: if two channels have the same setting (which is wrong!) the higher channel - // will get the setting. - - // First, reset all channel assignements: - QList fieldList = obj->getFields(); - foreach (UAVObjectField* field, fieldList) { - if (field->getUnits().contains("channel")) { - field->setValue(field->getOptions().last()); - } - } - - // Then assign according to current GUI state: - if (m_config->ch0Assign->currentIndex() != 0) { - field = obj->getField(m_config->ch0Assign->currentText()); - field->setValue(field->getOptions().at(0)); // -> This way we don't depend on channel naming convention - } - if (m_config->ch1Assign->currentIndex() != 0) { - field = obj->getField(m_config->ch1Assign->currentText()); - field->setValue(field->getOptions().at(1)); - } - if (m_config->ch2Assign->currentIndex() != 0) { - field = obj->getField(m_config->ch2Assign->currentText()); - field->setValue(field->getOptions().at(2)); - } - if (m_config->ch3Assign->currentIndex() != 0) { - field = obj->getField(m_config->ch3Assign->currentText()); - field->setValue(field->getOptions().at(3)); - } - if (m_config->ch4Assign->currentIndex() != 0) { - field = obj->getField(m_config->ch4Assign->currentText()); - field->setValue(field->getOptions().at(4)); - } - if (m_config->ch5Assign->currentIndex() != 0) { - field = obj->getField(m_config->ch5Assign->currentText()); - field->setValue(field->getOptions().at(5)); - } - if (m_config->ch6Assign->currentIndex() != 0) { - field = obj->getField(m_config->ch6Assign->currentText()); - field->setValue(field->getOptions().at(6)); - } - if (m_config->ch7Assign->currentIndex() != 0) { - field = obj->getField(m_config->ch7Assign->currentText()); - field->setValue(field->getOptions().at(7)); - } - - // Send all the flight mode settings - field = obj->getField(QString("FlightModePosition")); - field->setValue(m_config->fmsModePos1->currentText(),0); - field->setValue(m_config->fmsModePos2->currentText(),1); - field->setValue(m_config->fmsModePos3->currentText(),2); - - field = obj->getField(QString("Stabilization1Settings")); - field->setValue(m_config->fmsSsPos1Roll->currentText(), field->getElementNames().indexOf("Roll")); - field->setValue(m_config->fmsSsPos1Pitch->currentText(), field->getElementNames().indexOf("Pitch")); - field->setValue(m_config->fmsSsPos1Yaw->currentText(), field->getElementNames().indexOf("Yaw")); - field = obj->getField(QString("Stabilization2Settings")); - field->setValue(m_config->fmsSsPos2Roll->currentText(), field->getElementNames().indexOf("Roll")); - field->setValue(m_config->fmsSsPos2Pitch->currentText(), field->getElementNames().indexOf("Pitch")); - field->setValue(m_config->fmsSsPos2Yaw->currentText(), field->getElementNames().indexOf("Yaw")); - field = obj->getField(QString("Stabilization3Settings")); - field->setValue(m_config->fmsSsPos3Roll->currentText(), field->getElementNames().indexOf("Roll")); - field->setValue(m_config->fmsSsPos3Pitch->currentText(), field->getElementNames().indexOf("Pitch")); - field->setValue(m_config->fmsSsPos3Yaw->currentText(), field->getElementNames().indexOf("Yaw")); - - // Save the arming settings - field = obj->getField(QString("Arming")); - field->setValue(m_config->armControl->currentText()); - field = obj->getField(QString("ArmedTimeout")); - field->setValue(m_config->armTimeout->value()*1000); - - // ... and send to the OP Board - obj->updated(); } -/** - Sends the config to the board and request saving into the SD card - */ -void ConfigInputWidget::saveRCInputObject() +void ConfigInputWidget::resizeEvent(QResizeEvent *event) { - // Send update so that the latest value is saved - sendRCInputUpdate(); - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("ManualControlSettings"))); - Q_ASSERT(obj); - saveObjectToSD(obj); + QWidget::resizeEvent(event); + m_config->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio ); } - -/** - * Set the dropdown option for a channel Input assignement - */ -void ConfigInputWidget::assignChannel(UAVDataObject *obj, QString str) +void ConfigInputWidget::openHelp() { - UAVObjectField* field = obj->getField(str); - QStringList options = field->getOptions(); - switch (options.indexOf(field->getValue().toString())) { - case 0: - m_config->ch0Assign->setCurrentIndex(m_config->ch0Assign->findText(str)); - break; - case 1: - m_config->ch1Assign->setCurrentIndex(m_config->ch0Assign->findText(str)); - break; - case 2: - m_config->ch2Assign->setCurrentIndex(m_config->ch0Assign->findText(str)); - break; - case 3: - m_config->ch3Assign->setCurrentIndex(m_config->ch0Assign->findText(str)); - break; - case 4: - m_config->ch4Assign->setCurrentIndex(m_config->ch0Assign->findText(str)); - break; - case 5: - m_config->ch5Assign->setCurrentIndex(m_config->ch0Assign->findText(str)); - break; - case 6: - m_config->ch6Assign->setCurrentIndex(m_config->ch0Assign->findText(str)); - break; - case 7: - m_config->ch7Assign->setCurrentIndex(m_config->ch0Assign->findText(str)); - break; - } + + QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/Input+Configuration", QUrl::StrictMode) ); +} +void ConfigInputWidget::goToSimpleWizard() +{ + isSimple=true; + goToWizard(); +} +void ConfigInputWidget::goToNormalWizard() +{ + isSimple=false; + goToWizard(); +} +void ConfigInputWidget::goToWizard() +{ + QMessageBox msgBox; + msgBox.setText(tr("Arming Settings are now set to Always Disarmed for your safety.")); + msgBox.setDetailedText(tr("You will have to reconfigure arming settings yourself afterwards.")); + msgBox.setStandardButtons(QMessageBox::Ok); + msgBox.setDefaultButton(QMessageBox::Ok); + msgBox.exec(); + setupWizardWidget(wizardWelcome); + m_config->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio ); } -/** - * Updates the slider positions and min/max values - * - */ -void ConfigInputWidget::updateChannels(UAVObject* controlCommand) +void ConfigInputWidget::wzCancel() { - - QString fieldName = QString("Connected"); - UAVObjectField *field = controlCommand->getField(fieldName); - if (field->getValue().toBool()) + dimOtherControls(false); + manualCommandObj->setMetadata(manualCommandObj->getDefaultMetadata()); + m_config->stackedWidget->setCurrentIndex(0); + foreach (QWidget * wd, extraWidgets) { - m_config->RCInputConnected->setText("RC Receiver connected"); - m_config->lblMissingInputs->setText(""); + if(wd) + delete wd; + } + extraWidgets.clear(); + switch(wizardStep) + { + case wizardWelcome: + break; + case wizardChooseMode: + break; + case wizardIdentifySticks: + disconnect(receiverActivityObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyControls())); + break; + case wizardIdentifyCenter: + break; + case wizardIdentifyLimits: + disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyLimits())); + manualSettingsObj->setData(manualSettingsData); + break; + case wizardIdentifyInverted: + break; + case wizardFinish: + break; + default: + break; + } + wizardStep=wizardWelcome; +} + +void ConfigInputWidget::wzNext() +{ + setupWizardWidget(wizardStep+1); +} + +void ConfigInputWidget::wzBack() +{ + setupWizardWidget(wizardStep-1); +} + +void ConfigInputWidget::setupWizardWidget(int step) +{ + if(step==wizardWelcome) + { + m_config->graphicsView->setVisible(false); + setTxMovement(nothing); + if(wizardStep==wizardChooseMode) + { + delete extraWidgets.at(0); + delete extraWidgets.at(1); + extraWidgets.clear(); + } + manualSettingsData=manualSettingsObj->getData(); + manualSettingsData.Arming=ManualControlSettings::ARMING_ALWAYSDISARMED; + manualSettingsObj->setData(manualSettingsData); + m_config->wzText->setText(tr("Welcome to the inputs configuration wizard.\n" + "Please follow the instructions on the screen and only move your controls when asked to.\n" + "Make sure you already configured your hardware settings on the proper tab and restarted your board.\n" + "At any time you can press 'back' to return to the previous screeen or 'Cancel' to cancel the wizard.\n")); + m_config->stackedWidget->setCurrentIndex(1); + m_config->wzBack->setEnabled(false); + wizardStep=wizardWelcome; + } + else if(step==wizardChooseMode) + { + m_config->graphicsView->setVisible(true); + setTxMovement(nothing); + if(wizardStep==wizardIdentifySticks) + { + disconnect(receiverActivityObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyControls())); + m_config->wzNext->setEnabled(true); + } + m_config->wzText->setText(tr("Please choose your transmiter type.\n" + "Mode 1 means your throttle stick is on the right\n" + "Mode 2 means your throttle stick is on the left\n")); + m_config->wzBack->setEnabled(true); + QRadioButton * mode1=new QRadioButton(tr("Mode 1"),this); + QRadioButton * mode2=new QRadioButton(tr("Mode 2"),this); + mode2->setChecked(true); + extraWidgets.clear(); + extraWidgets.append(mode1); + extraWidgets.append(mode2); + m_config->checkBoxesLayout->layout()->addWidget(mode1); + m_config->checkBoxesLayout->layout()->addWidget(mode2); + wizardStep=wizardChooseMode; + } + else if(step==wizardIdentifySticks && !isSimple) + { + usedChannels.clear(); + if(wizardStep==wizardChooseMode) + { + QRadioButton * mode=qobject_cast(extraWidgets.at(0)); + if(mode->isChecked()) + transmitterMode=mode1; + else + transmitterMode=mode2; + delete extraWidgets.at(0); + delete extraWidgets.at(1); + extraWidgets.clear(); + } + wizardStep=wizardIdentifySticks; + currentCommand=0; + setMoveFromCommand(currentCommand); + m_config->wzText->setText(QString(tr("Please move each control once at a time according to the instructions and picture below.\n\n" + "Move the %1 stick")).arg(manualSettingsObj->getField("ChannelGroups")->getElementNames().at(currentCommand))); + manualSettingsData=manualSettingsObj->getData(); + connect(receiverActivityObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyControls())); + m_config->wzNext->setEnabled(false); + } + else if(step==wizardIdentifyCenter || (isSimple && step==wizardIdentifySticks)) + { + if(wizardStep==wizardChooseMode) + { + QRadioButton * mode=qobject_cast(extraWidgets.at(0)); + if(mode->isChecked()) + transmitterMode=mode1; + else + transmitterMode=mode2; + delete extraWidgets.at(0); + delete extraWidgets.at(1); + extraWidgets.clear(); + } + setTxMovement(centerAll); + if(wizardStep==wizardIdentifySticks) + disconnect(receiverActivityObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyControls())); + else + { + disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyLimits())); + manualSettingsObj->setData(manualSettingsData); + manualCommandObj->setMetadata(manualCommandObj->getDefaultMetadata()); + } + wizardStep=wizardIdentifyCenter; + m_config->wzText->setText(QString(tr("Please center all control controls and press next when ready (if your FlightMode switch has only two positions, leave it on either position)"))); + } + else if(step==wizardIdentifyLimits) + { + dimOtherControls(false); + setTxMovement(moveAll); + if(wizardStep==wizardIdentifyCenter) + { + wizardStep=wizardIdentifyLimits; + manualCommandData=manualCommandObj->getData(); + manualSettingsData=manualSettingsObj->getData(); + for(unsigned int i=0;isetData(manualSettingsData); + } + if(wizardStep==wizardIdentifyInverted) + { + foreach(QWidget * wd,extraWidgets) + { + QCheckBox * cb=qobject_cast(wd); + if(cb) + { + disconnect(cb,SIGNAL(toggled(bool)),this,SLOT(invertControls())); + delete cb; + } + } + } + extraWidgets.clear(); + disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); + wizardStep=wizardIdentifyLimits; + m_config->wzText->setText(QString(tr("Please move all controls to their maximum extents on both directions and press next when ready"))); + UAVObject::Metadata mdata= manualCommandObj->getMetadata(); + mdata.flightTelemetryUpdateMode = UAVObject::UPDATEMODE_PERIODIC; + mdata.flightTelemetryUpdatePeriod = 150; + manualCommandObj->setMetadata(mdata); + manualSettingsData=manualSettingsObj->getData(); + for(uint i=0;isetData(manualSettingsData); + } + extraWidgets.clear(); + foreach(QString name,manualSettingsObj->getFields().at(0)->getElementNames()) + { + if(!name.contains("Access") && !name.contains("Flight")) + { + QCheckBox * cb=new QCheckBox(name,this); + extraWidgets.append(cb); + m_config->checkBoxesLayout->layout()->addWidget(cb); + connect(cb,SIGNAL(toggled(bool)),this,SLOT(invertControls())); + } + } + connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); + wizardStep=wizardIdentifyInverted; + m_config->wzText->setText(QString(tr("Please check the picture below and check all the sticks which show an inverted movement and press next when ready"))); + } + else if(step==wizardFinish) + { + foreach(QWidget * wd,extraWidgets) + { + QCheckBox * cb=qobject_cast(wd); + if(cb) + { + disconnect(cb,SIGNAL(toggled(bool)),this,SLOT(invertControls())); + delete cb; + } + } + wizardStep=wizardFinish; + extraWidgets.clear(); + m_config->wzText->setText(QString(tr("You have completed this wizard, please check below if the picture below mimics your sticks movement.\n" + "This new settings aren't saved to the board yet, after pressing next you will go to the initial screen where you can do that."))); + + } + + else if(step==wizardFinish+1) + { + setTxMovement(nothing); + manualCommandObj->setMetadata(manualCommandObj->getDefaultMetadata()); + disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); + manualSettingsData=manualSettingsObj->getData(); + manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_THROTTLE]= + manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_THROTTLE]+ + ((manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_THROTTLE]- + manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_THROTTLE])*0.02); + if((abs(manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_FLIGHTMODE]-manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_FLIGHTMODE])<100) || + (abs(manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_FLIGHTMODE]-manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_FLIGHTMODE])<100)) + { + manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_FLIGHTMODE]=manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_FLIGHTMODE]+ + (manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_FLIGHTMODE]-manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_FLIGHTMODE])/2; + } + manualSettingsObj->setData(manualSettingsData); + m_config->stackedWidget->setCurrentIndex(0); + wizardStep=wizardWelcome; + } + +} + +void ConfigInputWidget::identifyControls() +{ + static int debounce=0; + receiverActivityData=receiverActivityObj->getData(); + if(receiverActivityData.ActiveChannel==255) + return; + else + { + receiverActivityData=receiverActivityObj->getData(); + currentChannel.group=receiverActivityData.ActiveGroup; + currentChannel.number=receiverActivityData.ActiveChannel; + if(currentChannel==lastChannel) + ++debounce; + lastChannel.group= currentChannel.group; + lastChannel.number=currentChannel.number; + if(!usedChannels.contains(lastChannel) && debounce>1) + { + debounce=0; + usedChannels.append(lastChannel); + manualSettingsData=manualSettingsObj->getData(); + manualSettingsData.ChannelGroups[currentCommand]=currentChannel.group; + manualSettingsData.ChannelNumber[currentCommand]=currentChannel.number; + manualSettingsObj->setData(manualSettingsData); + } + else + return; + } + ++currentCommand; + setMoveFromCommand(currentCommand); + if(currentCommand>ManualControlSettings::CHANNELGROUPS_NUMELEM-1) + { + disconnect(receiverActivityObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyControls())); + m_config->wzNext->setEnabled(true); + } + m_config->wzText->setText(QString(tr("Please move each control once at a time according to the instructions and picture below.\n\n" + "Move the %1 stick")).arg(manualSettingsObj->getFields().at(0)->getElementNames().at(currentCommand))); + if(manualSettingsObj->getField("ChannelGroups")->getElementNames().at(currentCommand).contains("Accessory")) + { + m_config->wzNext->setEnabled(true); + } +} + +void ConfigInputWidget::identifyLimits() +{ + manualCommandData=manualCommandObj->getData(); + for(uint i=0;imanualCommandData.Channel[i]) + manualSettingsData.ChannelMin[i]=manualCommandData.Channel[i]; + if(manualSettingsData.ChannelMax[i]start(100); + break; + case moveRightVerticalStick: + movePos=0; + growing=true; + currentMovement=moveRightVerticalStick; + animate->start(100); + break; + case moveLeftHorizontalStick: + movePos=0; + growing=true; + currentMovement=moveLeftHorizontalStick; + animate->start(100); + break; + case moveRightHorizontalStick: + movePos=0; + growing=true; + currentMovement=moveRightHorizontalStick; + animate->start(100); + break; + case moveAccess0: + movePos=0; + growing=true; + currentMovement=moveAccess0; + animate->start(100); + break; + case moveAccess1: + movePos=0; + growing=true; + currentMovement=moveAccess1; + animate->start(100); + break; + case moveAccess2: + movePos=0; + growing=true; + currentMovement=moveAccess2; + animate->start(100); + break; + case moveFlightMode: + movePos=0; + growing=true; + currentMovement=moveFlightMode; + animate->start(1000); + break; + case centerAll: + movePos=0; + currentMovement=centerAll; + animate->start(1000); + break; + case moveAll: + movePos=0; + growing=true; + currentMovement=moveAll; + animate->start(50); + break; + case nothing: + movePos=0; + animate->stop(); + break; + default: + break; + } +} + +void ConfigInputWidget::moveTxControls() +{ + QTransform trans; + QGraphicsItem * item; + txMovementType move; + int limitMax; + int limitMin; + static bool auxFlag=false; + switch(currentMovement) + { + case moveLeftVerticalStick: + item=m_txLeftStick; + trans=m_txLeftStickOrig; + limitMax=STICK_MAX_MOVE; + limitMin=STICK_MIN_MOVE; + move=vertical; + break; + case moveRightVerticalStick: + item=m_txRightStick; + trans=m_txRightStickOrig; + limitMax=STICK_MAX_MOVE; + limitMin=STICK_MIN_MOVE; + move=vertical; + break; + case moveLeftHorizontalStick: + item=m_txLeftStick; + trans=m_txLeftStickOrig; + limitMax=STICK_MAX_MOVE; + limitMin=STICK_MIN_MOVE; + move=horizontal; + break; + case moveRightHorizontalStick: + item=m_txRightStick; + trans=m_txRightStickOrig; + limitMax=STICK_MAX_MOVE; + limitMin=STICK_MIN_MOVE; + move=horizontal; + break; + case moveAccess0: + item=m_txAccess0; + trans=m_txAccess0Orig; + limitMax=ACCESS_MAX_MOVE; + limitMin=ACCESS_MIN_MOVE; + move=horizontal; + break; + case moveAccess1: + item=m_txAccess1; + trans=m_txAccess1Orig; + limitMax=ACCESS_MAX_MOVE; + limitMin=ACCESS_MIN_MOVE; + move=horizontal; + break; + case moveAccess2: + item=m_txAccess2; + trans=m_txAccess2Orig; + limitMax=ACCESS_MAX_MOVE; + limitMin=ACCESS_MIN_MOVE; + move=horizontal; + break; + case moveFlightMode: + item=m_txFlightMode; + move=jump; + break; + case centerAll: + item=m_txArrows; + move=jump; + break; + case moveAll: + limitMax=STICK_MAX_MOVE; + limitMin=STICK_MIN_MOVE; + move=mix; + break; + default: + break; + } + if(move==vertical) + item->setTransform(trans.translate(0,movePos*10),false); + else if(move==horizontal) + item->setTransform(trans.translate(movePos*10,0),false); + else if(move==jump) + { + if(item==m_txArrows) + { + m_txArrows->setVisible(!m_txArrows->isVisible()); + } + else if(item==m_txFlightMode) + { + QGraphicsSvgItem * svg; + svg=(QGraphicsSvgItem *)item; + if (svg) + { + if(svg->elementId()=="flightModeCenter") + { + if(growing) + { + svg->setElementId("flightModeRight"); + m_txFlightMode->setTransform(m_txFlightModeROrig,false); + } + else + { + svg->setElementId("flightModeLeft"); + m_txFlightMode->setTransform(m_txFlightModeLOrig,false); + } + } + else if(svg->elementId()=="flightModeRight") + { + growing=false; + svg->setElementId("flightModeCenter"); + m_txFlightMode->setTransform(m_txFlightModeCOrig,false); + } + else if(svg->elementId()=="flightModeLeft") + { + growing=true; + svg->setElementId("flightModeCenter"); + m_txFlightMode->setTransform(m_txFlightModeCOrig,false); + } + } + } + } + else if(move==mix) + { + trans=m_txAccess0Orig; + m_txAccess0->setTransform(trans.translate(movePos*10*ACCESS_MAX_MOVE/STICK_MAX_MOVE,0),false); + trans=m_txAccess1Orig; + m_txAccess1->setTransform(trans.translate(movePos*10*ACCESS_MAX_MOVE/STICK_MAX_MOVE,0),false); + trans=m_txAccess2Orig; + m_txAccess2->setTransform(trans.translate(movePos*10*ACCESS_MAX_MOVE/STICK_MAX_MOVE,0),false); + + if(auxFlag) + { + trans=m_txLeftStickOrig; + m_txLeftStick->setTransform(trans.translate(0,movePos*10),false); + trans=m_txRightStickOrig; + m_txRightStick->setTransform(trans.translate(0,movePos*10),false); + } + else + { + trans=m_txLeftStickOrig; + m_txLeftStick->setTransform(trans.translate(movePos*10,0),false); + trans=m_txRightStickOrig; + m_txRightStick->setTransform(trans.translate(movePos*10,0),false); + } + + if(movePos==0) + { + m_txFlightMode->setElementId("flightModeCenter"); + m_txFlightMode->setTransform(m_txFlightModeCOrig,false); + } + else if(movePos==ACCESS_MAX_MOVE/2) + { + m_txFlightMode->setElementId("flightModeRight"); + m_txFlightMode->setTransform(m_txFlightModeROrig,false); + } + else if(movePos==ACCESS_MIN_MOVE/2) + { + m_txFlightMode->setElementId("flightModeLeft"); + m_txFlightMode->setTransform(m_txFlightModeLOrig,false); + } + } + if(move==horizontal || move==vertical ||move==mix) + { + if(movePos==0 && growing) + auxFlag=!auxFlag; + if(growing) + ++movePos; + else + --movePos; + if(movePos>limitMax) + { + movePos=movePos-2; + growing=false; + } + if(movePosgetData(); + if(transmitterMode==mode2) + { + trans=m_txLeftStickOrig; + m_txLeftStick->setTransform(trans.translate(manualCommandData.Yaw*STICK_MAX_MOVE*10,-manualCommandData.Throttle*STICK_MAX_MOVE*10),false); + trans=m_txRightStickOrig; + m_txRightStick->setTransform(trans.translate(manualCommandData.Roll*STICK_MAX_MOVE*10,manualCommandData.Pitch*STICK_MAX_MOVE*10),false); } else { - m_config->RCInputConnected->setText("RC Receiver not connected or invalid input configuration (missing channels)"); - receiverHelp(); + trans=m_txRightStickOrig; + m_txRightStick->setTransform(trans.translate(manualCommandData.Roll*STICK_MAX_MOVE*10,-manualCommandData.Throttle*STICK_MAX_MOVE*10),false); + trans=m_txLeftStickOrig; + m_txLeftStick->setTransform(trans.translate(manualCommandData.Yaw*STICK_MAX_MOVE*10,manualCommandData.Pitch*STICK_MAX_MOVE*10),false); } - if (m_config->doRCInputCalibration->isChecked()) { - if (firstUpdate) { - // Increase the data rate from the board so that the sliders - // move faster - UAVObject::Metadata mdata = controlCommand->getMetadata(); - mdata.flightTelemetryUpdateMode = UAVObject::UPDATEMODE_PERIODIC; - mccDataRate = mdata.flightTelemetryUpdatePeriod; - mdata.flightTelemetryUpdatePeriod = 150; - controlCommand->setMetadata(mdata); +} - // Also protect the user by setting all values to zero - // and making the ActuatorCommand object readonly - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("ActuatorCommand"))); - mdata = obj->getMetadata(); - mdata.flightAccess = UAVObject::ACCESS_READONLY; - obj->setMetadata(mdata); - UAVObjectField *field = obj->getField("Channel"); - for (uint i=0; i< field->getNumElements(); i++) { - field->setValue(0,i); +void ConfigInputWidget::dimOtherControls(bool value) +{ + qreal opac; + if(value) + opac=0.1; + else + opac=1; + m_txAccess0->setOpacity(opac); + m_txAccess1->setOpacity(opac); + m_txAccess2->setOpacity(opac); + m_txFlightMode->setOpacity(opac); +} + +void ConfigInputWidget::enableControls(bool enable) +{ + if(goWizard) + { + goWizard->setEnabled(enable); + goSimpleWizard->setEnabled(enable); + } + ConfigTaskWidget::enableControls(enable); + +} + +void ConfigInputWidget::invertControls() +{ + manualSettingsData=manualSettingsObj->getData(); + foreach(QWidget * wd,extraWidgets) + { + QCheckBox * cb=qobject_cast(wd); + if(cb) + { + int index=manualSettingsObj->getFields().at(0)->getElementNames().indexOf(cb->text()); + if((cb->isChecked() && (manualSettingsData.ChannelMax[index]>manualSettingsData.ChannelMin[index])) || + (!cb->isChecked() && (manualSettingsData.ChannelMax[index]updated(); - - // OP-534: make sure the airframe can NEVER arm - obj = dynamic_cast(getObjectManager()->getObject(QString("ManualControlSettings"))); - field = obj->getField("Arming"); - field->setValue("Always Disarmed"); - obj->updated(); - - // Last, make sure the user won't apply/save during calibration - m_config->saveRCInputToRAM->setEnabled(false); - m_config->saveRCInputToSD->setEnabled(false); - - // Reset all slider values to zero - field = controlCommand->getField(QString("Channel")); - for (int i = 0; i < 8; i++) - updateChannelInSlider(inSliders[i], inMinLabels[i], inMaxLabels[i], field->getValue(i).toInt(),inRevCheckboxes[i]->isChecked()); - firstUpdate = false; - // Tell a few things to the user: - QMessageBox msgBox; - msgBox.setText(tr("Arming Settings are now set to Always Disarmed for your safety.")); - msgBox.setDetailedText(tr("You will have to reconfigure arming settings yourself afterwards.")); - msgBox.setStandardButtons(QMessageBox::Ok); - msgBox.setDefaultButton(QMessageBox::Ok); - msgBox.exec(); - } - - field = controlCommand->getField(QString("Channel")); - for (int i = 0; i < 8; i++) - updateChannelInSlider(inSliders[i], inMinLabels[i], inMaxLabels[i], field->getValue(i).toInt(),inRevCheckboxes[i]->isChecked()); } - else { - if (!firstUpdate) { - // Restore original data rate from the board: - UAVObject::Metadata mdata = controlCommand->getMetadata(); - mdata.flightTelemetryUpdateMode = UAVObject::UPDATEMODE_PERIODIC; - mdata.flightTelemetryUpdatePeriod = mccDataRate; - controlCommand->setMetadata(mdata); - - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("ActuatorCommand"))); - mdata = obj->getMetadata(); - mdata.flightAccess = UAVObject::ACCESS_READWRITE; - obj->setMetadata(mdata); - - // Set some slider values to better defaults - // Find some channels first - int throttleChannel = -1; - int fmChannel = -1; - for (int i=0; i < inChannelAssign.length(); i++) { - if (inChannelAssign.at(i)->currentText() == "Throttle") { - // TODO: this is very ugly, because this relies on the name of the - // channel input, everywhere else in the gadget we don't rely on the - // naming... - throttleChannel = i; - } - if (inChannelAssign.at(i)->currentText() == "FlightMode") { - // TODO: this is very ugly, because this relies on the name of the - // channel input, everywhere else in the gadget we don't rely on the - // naming... - fmChannel = i; - } - } - - // Throttle neutral defaults to 2% of range - if (throttleChannel > -1) { - inSliders.at(throttleChannel)->setValue( - inSliders.at(throttleChannel)->minimum() + - (inSliders.at(throttleChannel)->maximum()- - inSliders.at(throttleChannel)->minimum())*0.02); - } - - // Flight mode at 50% of range: - if (fmChannel > -1) { - inSliders.at(fmChannel)->setValue( - inSliders.at(fmChannel)->minimum()+ - (inSliders.at(fmChannel)->maximum()- - inSliders.at(fmChannel)->minimum())*0.5); - } - - m_config->saveRCInputToRAM->setEnabled(true); - m_config->saveRCInputToSD->setEnabled(true); - } - firstUpdate = true; - } - - //Update the Flight mode channel slider - ManualControlSettings * manualSettings = ManualControlSettings::GetInstance(getObjectManager()); - ManualControlSettings::DataFields manualSettingsData = manualSettings->getData(); - uint chIndex = manualSettingsData.FlightMode; - if (chIndex < manualSettings->FLIGHTMODE_NONE) { + manualSettingsObj->setData(manualSettingsData); +} +void ConfigInputWidget::moveFMSlider() +{ + ManualControlSettings::DataFields manualSettingsDataPriv = manualSettingsObj->getData(); + ManualControlCommand::DataFields manualCommandDataPriv=manualCommandObj->getData(); + uint chIndex = manualSettingsDataPriv.ChannelNumber[ManualControlSettings::CHANNELNUMBER_FLIGHTMODE]; + if (chIndex < 8) { float valueScaled; - int chMin = manualSettingsData.ChannelMin[chIndex]; - int chMax = manualSettingsData.ChannelMax[chIndex]; - int chNeutral = manualSettingsData.ChannelNeutral[chIndex]; + int chMin = manualSettingsDataPriv.ChannelMin[ManualControlSettings::CHANNELMIN_FLIGHTMODE]; + int chMax = manualSettingsDataPriv.ChannelMax[ManualControlSettings::CHANNELMAX_FLIGHTMODE]; + int chNeutral = manualSettingsDataPriv.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_FLIGHTMODE]; - int value = controlCommand->getField("Channel")->getValue(chIndex).toInt(); + int value = manualCommandDataPriv.Channel[chIndex]; if ((chMax > chMin && value >= chNeutral) || (chMin > chMax && value <= chNeutral)) { if (chMax != chNeutral) @@ -609,121 +976,5 @@ void ConfigInputWidget::updateChannels(UAVObject* controlCommand) m_config->fmsSlider->setValue(100); else m_config->fmsSlider->setValue(0); - - } -} - -void ConfigInputWidget::updateChannelInSlider(QSlider *slider, QLabel *min, QLabel *max, int value, bool reversed) -{ - if (!slider || !min || !max) - return; - - if (firstUpdate) { - // Reset all the min/max values of the progress bar since we are starting the calibration. - slider->setMaximum(value); - slider->setMinimum(value); - slider->setValue(value); - max->setText(QString::number(value)); - min->setText(QString::number(value)); - return; - } - - if (value > 0) { - // avoids glitches... - if (value > slider->maximum()) { - slider->setMaximum(value); - if (reversed) - min->setText(QString::number(value)); - else - max->setText(QString::number(value)); - } - if (value < slider->minimum()) { - slider->setMinimum(value); - if (reversed) - max->setText(QString::number(value)); - else - min->setText(QString::number(value)); - } - slider->setValue(value); - } -} - -void ConfigInputWidget::openHelp() -{ - - QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/Input+Configuration", QUrl::StrictMode) ); -} -void ConfigInputWidget::receiverHelp() -{ - QString unassigned; - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager *objManager = pm->getObject(); - UAVDataObject* controlCommand = dynamic_cast(objManager->getObject(QString("ManualControlSettings"))); - - UAVObjectField *field; - - field= controlCommand->getField("Roll"); - if(field->getValue().toString()=="None") - unassigned.append("Roll"); - - field =controlCommand->getField("Pitch"); - if(field->getValue().toString()=="None") - { - if(unassigned.length()>0) - unassigned.append(", "); - unassigned.append("Pitch"); - } - - field =controlCommand->getField("Yaw"); - if(field->getValue().toString()=="None") - { - if(unassigned.length()>0) - unassigned.append(", "); - unassigned.append("Yaw"); - } - - field =controlCommand->getField("Throttle"); - if(field->getValue().toString()=="None") - { - if(unassigned.length()>0) - unassigned.append(", "); - unassigned.append("Throttle"); - } - - field =controlCommand->getField("FlightMode"); - if(field->getValue().toString()=="None") - { - if(unassigned.length()>0) - unassigned.append(", "); - unassigned.append("FlightMode"); - } - if(unassigned.length()>0) - m_config->lblMissingInputs->setText(QString("Channels left to assign: ")+unassigned); - else - m_config->lblMissingInputs->setText(""); -} -void ConfigInputWidget::updateTips(int value) -{ - if(value==Qt::Checked) - { - m_config->ch0Cur->setToolTip("Current channel value"); - m_config->ch1Cur->setToolTip("Current channel value"); - m_config->ch2Cur->setToolTip("Current channel value"); - m_config->ch3Cur->setToolTip("Current channel value"); - m_config->ch4Cur->setToolTip("Current channel value"); - m_config->ch5Cur->setToolTip("Current channel value"); - m_config->ch6Cur->setToolTip("Current channel value"); - m_config->ch7Cur->setToolTip("Current channel value"); - } - else - { - m_config->ch0Cur->setToolTip("Channel neutral point"); - m_config->ch1Cur->setToolTip("Channel neutral point"); - m_config->ch2Cur->setToolTip("Channel neutral point"); - m_config->ch3Cur->setToolTip("Channel neutral point"); - m_config->ch4Cur->setToolTip("Channel neutral point"); - m_config->ch5Cur->setToolTip("Channel neutral point"); - m_config->ch6Cur->setToolTip("Channel neutral point"); - m_config->ch7Cur->setToolTip("Channel neutral point"); } } diff --git a/ground/openpilotgcs/src/plugins/config/configinputwidget.h b/ground/openpilotgcs/src/plugins/config/configinputwidget.h index 75f47cc8d..2249528cb 100644 --- a/ground/openpilotgcs/src/plugins/config/configinputwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configinputwidget.h @@ -34,52 +34,111 @@ #include "uavobject.h" #include #include +#include "inputchannelform.h" +#include "ui_inputchannelform.h" +#include +#include "manualcontrolcommand.h" +#include "manualcontrolsettings.h" +#include "receiveractivity.h" +#include +#include +#include class Ui_InputWidget; class ConfigInputWidget: public ConfigTaskWidget { Q_OBJECT - public: ConfigInputWidget(QWidget *parent = 0); ~ConfigInputWidget(); - + enum wizardSteps{wizardWelcome,wizardChooseMode,wizardIdentifySticks,wizardIdentifyCenter,wizardIdentifyLimits,wizardIdentifyInverted,wizardFinish}; + enum txMode{mode1,mode2}; + enum txMovements{moveLeftVerticalStick,moveRightVerticalStick,moveLeftHorizontalStick,moveRightHorizontalStick,moveAccess0,moveAccess1,moveAccess2,moveFlightMode,centerAll,moveAll,nothing}; + enum txMovementType{vertical,horizontal,jump,mix}; public slots: private: + bool growing; + txMovements currentMovement; + int movePos; + void setTxMovement(txMovements movement); Ui_InputWidget *m_config; + wizardSteps wizardStep; + void setupWizardWidget(int step); + QList extraWidgets; + txMode transmitterMode; + struct channelsStruct + { + bool operator ==(const channelsStruct& rhs) const + { + return((group==rhs.group) &&(number==rhs.number)); + } + int group; + int number; + }lastChannel; + channelsStruct currentChannel; + QList usedChannels; + QEventLoop * loop; + bool skipflag; - QList sliders; + uint currentCommand; - void updateChannelInSlider(QSlider *slider, QLabel *min, QLabel *max, int value, bool reversed); + ManualControlCommand * manualCommandObj; + ManualControlCommand::DataFields manualCommandData; + ManualControlSettings * manualSettingsObj; + ManualControlSettings::DataFields manualSettingsData; + ReceiverActivity * receiverActivityObj; + ReceiverActivity::DataFields receiverActivityData; - void assignChannel(UAVDataObject *obj, QString str); - void assignOutputChannel(UAVDataObject *obj, QString str); + QSvgRenderer *m_renderer; - int mccDataRate; - - UAVObject::Metadata accInitialData; - - QList inSliders; - QList inMaxLabels; - QList inMinLabels; - QList inNeuLabels; - QList inRevCheckboxes; - QList inChannelAssign; - - bool firstUpdate; - - virtual void enableControls(bool enable); - void receiverHelp(); + // Background: background + QGraphicsSvgItem *m_txMainBody; + QGraphicsSvgItem *m_txLeftStick; + QGraphicsSvgItem *m_txRightStick; + QGraphicsSvgItem *m_txAccess0; + QGraphicsSvgItem *m_txAccess1; + QGraphicsSvgItem *m_txAccess2; + QGraphicsSvgItem *m_txFlightMode; + QGraphicsSvgItem *m_txBackground; + QGraphicsSvgItem *m_txArrows; + QTransform m_txLeftStickOrig; + QTransform m_txRightStickOrig; + QTransform m_txAccess0Orig; + QTransform m_txAccess1Orig; + QTransform m_txAccess2Orig; + QTransform m_txFlightModeCOrig; + QTransform m_txFlightModeLOrig; + QTransform m_txFlightModeROrig; + QTransform m_txMainBodyOrig; + QTransform m_txArrowsOrig; + QTimer * animate; + void resetTxControls(); + void setMoveFromCommand(int command); + QPushButton * goWizard; + QPushButton * goSimpleWizard; + bool isSimple; + void goToWizard(); private slots: - void updateChannels(UAVObject* obj); - virtual void refreshValues(); - void sendRCInputUpdate(); - void saveRCInputObject(); - void reverseCheckboxClicked(bool state); + void wzNext(); + void wzBack(); + void wzCancel(); + void goToNormalWizard(); + void goToSimpleWizard(); void openHelp(); - void updateTips(int); + void identifyControls(); + void identifyLimits(); + void moveTxControls(); + void moveSticks(); + void dimOtherControls(bool value); + void moveFMSlider(); + void invertControls(); +protected: + void resizeEvent(QResizeEvent *event); + virtual void enableControls(bool enable); + + }; #endif diff --git a/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp index 1a961805b..0adc41e2c 100644 --- a/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp @@ -45,7 +45,8 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren m_config->setupUi(this); ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager *objManager = pm->getObject(); + setupButtons(m_config->saveRCOutputToRAM,m_config->saveRCOutputToSD); + addUAVObject("ActuatorSettings"); // First of all, put all the channel widgets into lists, so that we can // manipulate those: @@ -106,10 +107,7 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren << m_config->ch7Link; // Register for ActuatorSettings changes: - UAVDataObject * obj = dynamic_cast(objManager->getObject(QString("ActuatorSettings"))); - connect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(refreshValues())); - - for (int i = 0; i < 8; i++) { + for (int i = 0; i < 8; i++) { connect(outMin[i], SIGNAL(editingFinished()), this, SLOT(setChOutRange())); connect(outMax[i], SIGNAL(editingFinished()), this, SLOT(setChOutRange())); connect(reversals[i], SIGNAL(toggled(bool)), this, SLOT(reverseChannel(bool))); @@ -124,13 +122,8 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren for (int i = 0; i < links.count(); i++) connect(links[i], SIGNAL(toggled(bool)), this, SLOT(linkToggled(bool))); - connect(m_config->saveRCOutputToSD, SIGNAL(clicked()), this, SLOT(saveRCOutputObject())); - connect(m_config->saveRCOutputToRAM, SIGNAL(clicked()), this, SLOT(sendRCOutputUpdate())); - enableControls(false); - refreshValues(); - connect(parent, SIGNAL(autopilotConnected()),this, SLOT(onAutopilotConnect())); - connect(parent, SIGNAL(autopilotDisconnected()), this, SLOT(onAutopilotDisconnect())); + refreshWidgetsValues(); firstUpdate = true; @@ -138,6 +131,43 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren // Connect the help button connect(m_config->outputHelp, SIGNAL(clicked()), this, SLOT(openHelp())); + addWidget(m_config->outputRate3); + addWidget(m_config->outputRate2); + addWidget(m_config->outputRate1); + addWidget(m_config->ch0OutMin); + addWidget(m_config->ch0OutSlider); + addWidget(m_config->ch0OutMax); + addWidget(m_config->ch0Rev); + addWidget(m_config->ch0Link); + addWidget(m_config->ch1OutMin); + addWidget(m_config->ch1OutSlider); + addWidget(m_config->ch1OutMax); + addWidget(m_config->ch1Rev); + addWidget(m_config->ch2OutMin); + addWidget(m_config->ch2OutSlider); + addWidget(m_config->ch2OutMax); + addWidget(m_config->ch2Rev); + addWidget(m_config->ch3OutMin); + addWidget(m_config->ch3OutSlider); + addWidget(m_config->ch3OutMax); + addWidget(m_config->ch3Rev); + addWidget(m_config->ch4OutMin); + addWidget(m_config->ch4OutSlider); + addWidget(m_config->ch4OutMax); + addWidget(m_config->ch4Rev); + addWidget(m_config->ch5OutMin); + addWidget(m_config->ch5OutSlider); + addWidget(m_config->ch5OutMax); + addWidget(m_config->ch5Rev); + addWidget(m_config->ch6OutMin); + addWidget(m_config->ch6OutSlider); + addWidget(m_config->ch6OutMax); + addWidget(m_config->ch6Rev); + addWidget(m_config->ch7OutMin); + addWidget(m_config->ch7OutSlider); + addWidget(m_config->ch7OutMax); + addWidget(m_config->ch7Rev); + addWidget(m_config->spinningArmed); } ConfigOutputWidget::~ConfigOutputWidget() @@ -146,14 +176,6 @@ ConfigOutputWidget::~ConfigOutputWidget() } -// ************************************ - -void ConfigOutputWidget::enableControls(bool enable) -{ - m_config->saveRCOutputToSD->setEnabled(enable); - //m_config->saveRCOutputToRAM->setEnabled(enable); -} - // ************************************ /** @@ -355,8 +377,9 @@ void ConfigOutputWidget::sendChannelTest(int value) /** Request the current config from the board (RC Output) */ -void ConfigOutputWidget::refreshValues() +void ConfigOutputWidget::refreshWidgetsValues() { + bool dirty=isDirty(); ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); UAVObjectManager *objManager = pm->getObject(); @@ -444,14 +467,14 @@ void ConfigOutputWidget::refreshValues() outSliders[i]->setValue(value); outLabels[i]->setText(QString::number(value)); } - + setDirty(dirty); } /** * Sends the config to the board, without saving to the SD card (RC Output) */ -void ConfigOutputWidget::sendRCOutputUpdate() +void ConfigOutputWidget::updateObjectsFromWidgets() { ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); UAVObjectManager *objManager = pm->getObject(); @@ -479,27 +502,8 @@ void ConfigOutputWidget::sendRCOutputUpdate() field->setValue(m_config->outputRate2->value(),1); field->setValue(m_config->outputRate3->value(),2); field->setValue(m_config->outputRate4->value(),3); - - // ... and send to the OP Board - obj->updated(); - } - -/** - Sends the config to the board and request saving into the SD card (RC Output) - */ -void ConfigOutputWidget::saveRCOutputObject() -{ - // Send update so that the latest value is saved - sendRCOutputUpdate(); - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("ActuatorSettings"))); - Q_ASSERT(obj); - saveObjectToSD(obj); - -} - - /** Sets the minimum/maximum value of the channel 0 to seven output sliders. Have to do it here because setMinimum is not a slot. diff --git a/ground/openpilotgcs/src/plugins/config/configoutputwidget.h b/ground/openpilotgcs/src/plugins/config/configoutputwidget.h index 2a197e3ac..492109df1 100644 --- a/ground/openpilotgcs/src/plugins/config/configoutputwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configoutputwidget.h @@ -69,12 +69,10 @@ private: bool firstUpdate; - virtual void enableControls(bool enable); private slots: - virtual void refreshValues(); - void sendRCOutputUpdate(); - void saveRCOutputObject(); + virtual void refreshWidgetsValues(); + void updateObjectsFromWidgets(); void runChannelTests(bool state); void sendChannelTest(int value); void setChOutRange(); diff --git a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp index 5cd0cfa04..cbe554f4e 100644 --- a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp @@ -43,21 +43,15 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa m_stabilization->setupUi(this); - connect(m_stabilization->saveStabilizationToSD, SIGNAL(clicked()), this, SLOT(saveStabilizationUpdate())); - connect(m_stabilization->saveStabilizationToRAM, SIGNAL(clicked()), this, SLOT(sendStabilizationUpdate())); + setupButtons(m_stabilization->saveStabilizationToRAM,m_stabilization->saveStabilizationToSD); - enableControls(false); - refreshValues(); - connect(parent, SIGNAL(autopilotConnected()),this, SLOT(onAutopilotConnect())); - connect(parent, SIGNAL(autopilotDisconnected()),this, SLOT(onAutopilotDisconnect())); + addUAVObject("StabilizationSettings"); - // Now connect the widget to the StabilizationSettings object - UAVObject *obj = getObjectManager()->getObject(QString("StabilizationSettings")); - connect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(refreshValues())); + refreshWidgetsValues(); // Create a timer to regularly send the object update in case // we want realtime updates. - connect(&updateTimer, SIGNAL(timeout()), this, SLOT(sendStabilizationUpdate())); + connect(&updateTimer, SIGNAL(timeout()), this, SLOT(updateObjectsFromWidgets())); connect(m_stabilization->realTimeUpdates, SIGNAL(toggled(bool)), this, SLOT(realtimeUpdateToggle(bool))); // Connect the updates of the stab values @@ -79,6 +73,35 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa // Connect the help button connect(m_stabilization->stabilizationHelp, SIGNAL(clicked()), this, SLOT(openHelp())); + addWidget(m_stabilization->rateRollKp); + addWidget(m_stabilization->rateRollKi); + addWidget(m_stabilization->rateRollILimit); + addWidget(m_stabilization->ratePitchKp); + addWidget(m_stabilization->ratePitchKi); + addWidget(m_stabilization->ratePitchILimit); + addWidget(m_stabilization->rateYawKp); + addWidget(m_stabilization->rateYawKi); + addWidget(m_stabilization->rateYawILimit); + addWidget(m_stabilization->rollKp); + addWidget(m_stabilization->rollKi); + addWidget(m_stabilization->rollILimit); + addWidget(m_stabilization->yawILimit); + addWidget(m_stabilization->yawKi); + addWidget(m_stabilization->yawKp); + addWidget(m_stabilization->pitchKp); + addWidget(m_stabilization->pitchKi); + addWidget(m_stabilization->pitchILimit); + addWidget(m_stabilization->rollMax); + addWidget(m_stabilization->pitchMax); + addWidget(m_stabilization->yawMax); + addWidget(m_stabilization->manualRoll); + addWidget(m_stabilization->manualPitch); + addWidget(m_stabilization->manualYaw); + addWidget(m_stabilization->maximumRoll); + addWidget(m_stabilization->maximumPitch); + addWidget(m_stabilization->maximumYaw); + addWidget(m_stabilization->lowThrottleZeroIntegral); + } ConfigStabilizationWidget::~ConfigStabilizationWidget() @@ -86,13 +109,6 @@ ConfigStabilizationWidget::~ConfigStabilizationWidget() // Do nothing } - -void ConfigStabilizationWidget::enableControls(bool enable) -{ - //m_stabilization->saveStabilizationToRAM->setEnabled(enable); - m_stabilization->saveStabilizationToSD->setEnabled(enable); -} - void ConfigStabilizationWidget::updateRateRollKP(double val) { if (m_stabilization->linkRateRP->isChecked()) { @@ -187,8 +203,9 @@ void ConfigStabilizationWidget::updatePitchILimit(double val) /** Request stabilization settings from the board */ -void ConfigStabilizationWidget::refreshValues() +void ConfigStabilizationWidget::refreshWidgetsValues() { + bool dirty=isDirty(); // Not needed anymore as this slot is only called whenever we get // a signal that the object was just updated // stabSettings->requestUpdate(); @@ -229,9 +246,9 @@ void ConfigStabilizationWidget::refreshValues() m_stabilization->maximumRoll->setValue(stabData.MaximumRate[StabilizationSettings::MAXIMUMRATE_ROLL]); m_stabilization->maximumPitch->setValue(stabData.MaximumRate[StabilizationSettings::MAXIMUMRATE_PITCH]); m_stabilization->maximumYaw->setValue(stabData.MaximumRate[StabilizationSettings::MAXIMUMRATE_YAW]); + m_stabilization->lowThrottleZeroIntegral->setChecked(stabData.LowThrottleZeroIntegral==StabilizationSettings::LOWTHROTTLEZEROINTEGRAL_TRUE ? true : false); - m_stabilization->lowThrottleZeroIntegral->setChecked( - stabData.LowThrottleZeroIntegral == StabilizationSettings::LOWTHROTTLEZEROINTEGRAL_TRUE); + setDirty(dirty); } @@ -239,7 +256,7 @@ void ConfigStabilizationWidget::refreshValues() Send telemetry settings to the board */ -void ConfigStabilizationWidget::sendStabilizationUpdate() +void ConfigStabilizationWidget::updateObjectsFromWidgets() { StabilizationSettings::DataFields stabData = stabSettings->getData(); @@ -279,28 +296,12 @@ void ConfigStabilizationWidget::sendStabilizationUpdate() stabData.MaximumRate[StabilizationSettings::MAXIMUMRATE_PITCH] = m_stabilization->maximumPitch->value(); stabData.MaximumRate[StabilizationSettings::MAXIMUMRATE_YAW] = m_stabilization->maximumYaw->value(); - stabData.LowThrottleZeroIntegral = m_stabilization->lowThrottleZeroIntegral->isChecked() ? - StabilizationSettings::LOWTHROTTLEZEROINTEGRAL_TRUE : - StabilizationSettings::LOWTHROTTLEZEROINTEGRAL_FALSE; + stabData.LowThrottleZeroIntegral = (m_stabilization->lowThrottleZeroIntegral->isChecked() ? StabilizationSettings::LOWTHROTTLEZEROINTEGRAL_TRUE :StabilizationSettings::LOWTHROTTLEZEROINTEGRAL_FALSE); + stabSettings->setData(stabData); // this is atomic } - -/** - Send telemetry settings to the board and request saving to SD card - */ - -void ConfigStabilizationWidget::saveStabilizationUpdate() -{ - // Send update so that the latest value is saved - sendStabilizationUpdate(); - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("StabilizationSettings"))); - Q_ASSERT(obj); - saveObjectToSD(obj); -} - - void ConfigStabilizationWidget::realtimeUpdateToggle(bool state) { if (state) { diff --git a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h index 98db5530f..e512c5097 100644 --- a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h @@ -49,12 +49,10 @@ private: Ui_StabilizationWidget *m_stabilization; StabilizationSettings* stabSettings; QTimer updateTimer; - virtual void enableControls(bool enable); private slots: - virtual void refreshValues(); - void sendStabilizationUpdate(); - void saveStabilizationUpdate(); + virtual void refreshWidgetsValues(); + void updateObjectsFromWidgets(); void realtimeUpdateToggle(bool); void openHelp(); diff --git a/ground/openpilotgcs/src/plugins/config/configtaskwidget.cpp b/ground/openpilotgcs/src/plugins/config/configtaskwidget.cpp index 8fd35c596..eeb6c08aa 100644 --- a/ground/openpilotgcs/src/plugins/config/configtaskwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configtaskwidget.cpp @@ -28,7 +28,7 @@ #include -ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent),smartsave(NULL),dirty(false) +ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent),isConnected(false),smartsave(NULL),dirty(false) { pm = ExtensionSystem::PluginManager::instance(); objManager = pm->getObject(); @@ -43,13 +43,24 @@ void ConfigTaskWidget::addUAVObject(QString objectName) { addUAVObjectToWidgetRelation(objectName,"",NULL); } -void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget * widget) +void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget * widget, QString index) +{ + UAVObject *obj=NULL; + UAVObjectField *_field=NULL; + obj = objManager->getObject(QString(object)); + _field = obj->getField(QString(field)); + addUAVObjectToWidgetRelation(object,field,widget,_field->getElementNames().indexOf(index)); +} + +void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget * widget, int index,int scale) { UAVObject *obj=NULL; UAVObjectField *_field=NULL; if(!object.isEmpty()) + { obj = objManager->getObject(QString(object)); - connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues())); + connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues())); + } //smartsave->addObject(obj); if(!field.isEmpty() && obj) _field = obj->getField(QString(field)); @@ -57,9 +68,11 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString fiel ow->field=_field; ow->object=obj; ow->widget=widget; + ow->index=index; + ow->scale=scale; objOfInterest.append(ow); if(obj) - smartsave->addObject(obj); + smartsave->addObject((UAVDataObject*)obj); if(widget==NULL) { // do nothing @@ -88,6 +101,15 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString fiel { connect(cb,SIGNAL(valueChanged(double)),this,SLOT(widgetsContentsChanged())); } + else if(QCheckBox * cb=qobject_cast(widget)) + { + connect(cb,SIGNAL(clicked()),this,SLOT(widgetsContentsChanged())); + } + else if(QPushButton * cb=qobject_cast(widget)) + { + connect(cb,SIGNAL(clicked()),this,SLOT(widgetsContentsChanged())); + } + } @@ -126,17 +148,21 @@ double ConfigTaskWidget::listMean(QList list) void ConfigTaskWidget::onAutopilotDisconnect() { - enableControls(false); + isConnected=false; + enableControls(false); } void ConfigTaskWidget::onAutopilotConnect() { - enableControls(true); - refreshWidgetsValues(); + dirty=false; + isConnected=true; + enableControls(true); + refreshWidgetsValues(); } void ConfigTaskWidget::populateWidgets() { + bool dirtyBack=dirty; foreach(objectToWidget * ow,objOfInterest) { if(ow->object==NULL || ow->field==NULL) @@ -146,18 +172,23 @@ void ConfigTaskWidget::populateWidgets() else if(QComboBox * cb=qobject_cast(ow->widget)) { cb->addItems(ow->field->getOptions()); - cb->setCurrentIndex(cb->findText(ow->field->getValue().toString())); + cb->setCurrentIndex(cb->findText(ow->field->getValue(ow->index).toString())); } else if(QLabel * cb=qobject_cast(ow->widget)) { - cb->setText(ow->field->getValue().toString()); + cb->setText(ow->field->getValue(ow->index).toString()); + } + else if(QSpinBox * cb=qobject_cast(ow->widget)) + { + cb->setValue(ow->field->getValue(ow->index).toInt()/ow->scale); } } - dirty=false; + setDirty(dirtyBack); } void ConfigTaskWidget::refreshWidgetsValues() { + bool dirtyBack=dirty; foreach(objectToWidget * ow,objOfInterest) { if(ow->object==NULL || ow->field==NULL) @@ -166,13 +197,18 @@ void ConfigTaskWidget::refreshWidgetsValues() } else if(QComboBox * cb=qobject_cast(ow->widget)) { - cb->setCurrentIndex(cb->findText(ow->field->getValue().toString())); + cb->setCurrentIndex(cb->findText(ow->field->getValue(ow->index).toString())); } else if(QLabel * cb=qobject_cast(ow->widget)) { - cb->setText(ow->field->getValue().toString()); + cb->setText(ow->field->getValue(ow->index).toString()); + } + else if(QSpinBox * cb=qobject_cast(ow->widget)) + { + cb->setValue(ow->field->getValue(ow->index).toInt()/ow->scale); } } + setDirty(dirtyBack); } void ConfigTaskWidget::updateObjectsFromWidgets() @@ -185,11 +221,15 @@ void ConfigTaskWidget::updateObjectsFromWidgets() } else if(QComboBox * cb=qobject_cast(ow->widget)) { - ow->field->setValue(cb->currentText()); + ow->field->setValue(cb->currentText(),ow->index); } else if(QLabel * cb=qobject_cast(ow->widget)) { - ow->field->setValue(cb->text()); + ow->field->setValue(cb->text(),ow->index); + } + else if(QSpinBox * cb=qobject_cast(ow->widget)) + { + ow->field->setValue(cb->value()* ow->scale,ow->index); } } } @@ -197,10 +237,11 @@ void ConfigTaskWidget::updateObjectsFromWidgets() void ConfigTaskWidget::setupButtons(QPushButton *update, QPushButton *save) { smartsave=new smartSaveButton(update,save); - connect(smartsave, SIGNAL(preProcessOperations()), this, SLOT(updateObjectsFromWidgets())); + connect(smartsave,SIGNAL(preProcessOperations()), this, SLOT(updateObjectsFromWidgets())); connect(smartsave,SIGNAL(saveSuccessfull()),this,SLOT(clearDirty())); connect(smartsave,SIGNAL(beginOp()),this,SLOT(disableObjUpdates())); connect(smartsave,SIGNAL(endOp()),this,SLOT(enableObjUpdates())); + enableControls(false); } void ConfigTaskWidget::enableControls(bool enable) @@ -211,17 +252,23 @@ void ConfigTaskWidget::enableControls(bool enable) void ConfigTaskWidget::widgetsContentsChanged() { - dirty=true; + setDirty(true); } void ConfigTaskWidget::clearDirty() { - dirty=false; + setDirty(false); +} +void ConfigTaskWidget::setDirty(bool value) +{ + dirty=value; } - bool ConfigTaskWidget::isDirty() { - return dirty; + if(isConnected) + return dirty; + else + return false; } void ConfigTaskWidget::refreshValues() diff --git a/ground/openpilotgcs/src/plugins/config/configtaskwidget.h b/ground/openpilotgcs/src/plugins/config/configtaskwidget.h index bd293ce5f..b2a72cbc6 100644 --- a/ground/openpilotgcs/src/plugins/config/configtaskwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configtaskwidget.h @@ -41,6 +41,9 @@ #include #include #include +#include +#include + class ConfigTaskWidget: public QWidget { Q_OBJECT @@ -51,6 +54,8 @@ public: UAVObject * object; UAVObjectField * field; QWidget * widget; + int index; + int scale; }; ConfigTaskWidget(QWidget *parent = 0); @@ -60,9 +65,12 @@ public: static double listMean(QList list); void addUAVObject(QString objectName); void addWidget(QWidget * widget); - void addUAVObjectToWidgetRelation(QString object,QString field,QWidget * widget); + void addUAVObjectToWidgetRelation(QString object,QString field,QWidget * widget,int index=0,int scale=1); + void setupButtons(QPushButton * update,QPushButton * save); bool isDirty(); + void setDirty(bool value); + void addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, QString index); public slots: void onAutopilotDisconnect(); void onAutopilotConnect(); @@ -71,6 +79,8 @@ private slots: virtual void refreshValues(); virtual void updateObjectsFromWidgets(); private: + bool isConnected; + QStringList objectsList; QList objOfInterest; ExtensionSystem::PluginManager *pm; UAVObjectManager *objManager; diff --git a/ground/openpilotgcs/src/plugins/config/fancytabwidget.cpp b/ground/openpilotgcs/src/plugins/config/fancytabwidget.cpp index 97ae45303..bb0b65b09 100644 --- a/ground/openpilotgcs/src/plugins/config/fancytabwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/fancytabwidget.cpp @@ -284,6 +284,10 @@ void FancyTabBar::paintTab(QPainter *painter, int tabIndex) const } void FancyTabBar::setCurrentIndex(int index) { + bool proceed=true; + emit aboutToChange(&proceed); + if(!proceed) + return; m_currentIndex = index; update(); emit currentChanged(index); @@ -319,7 +323,6 @@ FancyTabWidget::FancyTabWidget(QWidget *parent, bool isVertical) : QWidget(parent) { m_tabBar = new FancyTabBar(this, isVertical); - m_selectionWidget = new QWidget(this); QBoxLayout *selectionLayout; if (isVertical) { @@ -477,3 +480,7 @@ void FancyTabWidget::setTabToolTip(int index, const QString &toolTip) { m_tabBar->setTabToolTip(index, toolTip); } +QWidget * FancyTabWidget::currentWidget() +{ + return m_modesStack->currentWidget(); +} diff --git a/ground/openpilotgcs/src/plugins/config/fancytabwidget.h b/ground/openpilotgcs/src/plugins/config/fancytabwidget.h index 47c7ddeb5..73da2aae8 100644 --- a/ground/openpilotgcs/src/plugins/config/fancytabwidget.h +++ b/ground/openpilotgcs/src/plugins/config/fancytabwidget.h @@ -91,6 +91,7 @@ public: signals: void currentChanged(int); + void aboutToChange(bool *); public slots: void updateHover(); @@ -116,7 +117,7 @@ class FancyTabWidget : public QWidget public: FancyTabWidget(QWidget *parent = 0, bool isVertical = false); - + FancyTabBar *m_tabBar; void insertTab(int index, QWidget *tab, const QIcon &icon, const QString &label); void removeTab(int index); void setBackgroundBrush(const QBrush &brush); @@ -132,6 +133,7 @@ public: int currentIndex() const; QStatusBar *statusBar() const; + QWidget * currentWidget(); signals: void currentAboutToShow(int index); void currentChanged(int index); @@ -143,7 +145,6 @@ private slots: void showWidget(int index); private: - FancyTabBar *m_tabBar; QWidget *m_cornerWidgetContainer; QStackedLayout *m_modesStack; QWidget *m_selectionWidget; diff --git a/ground/openpilotgcs/src/plugins/config/images/TX.svg b/ground/openpilotgcs/src/plugins/config/images/TX.svg new file mode 100644 index 000000000..ebfee4463 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/images/TX.svg @@ -0,0 +1,571 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + image/svg+xml + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Flight Mode + + Accessory2 + + + + Accessory1 + + + Accessory0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/config/input.ui b/ground/openpilotgcs/src/plugins/config/input.ui index e1eb0b435..0ec15f063 100644 --- a/ground/openpilotgcs/src/plugins/config/input.ui +++ b/ground/openpilotgcs/src/plugins/config/input.ui @@ -25,770 +25,81 @@ - - - - 75 - true - - - - Receiver Type: - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - - - 234 - 54 - - - - - 75 - true - - - - Indicates whether OpenPilot is getting a signal from the RC receiver. - - - RC Receiver not connected or invalid input configuration (missing channels) - - - true - - - - - - - - - Rev. - - - Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft - - - - - - - - 16 - 16 - - - - true - - - - - - - true - - - 1000 - - - 2000 - - - 1500 - - - Qt::Horizontal - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Maximum channel pulse width</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html> - - - 2000 - - - - - - - Check this to reverse the channel. -(Useful for transmitters without channel -reversal capabilities). - - - - - - - - - - - - - true - - - 1000 - - - 2000 - - - 1500 - - - Qt::Horizontal - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Maximum channel pulse width</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html> - - - 2000 - - - - - - - Check this to reverse the channel. -(Useful for transmitters without channel -reversal capabilities). - - - - - - - - - - - - - true - - - 1000 - - - 2000 - - - 1500 - - - Qt::Horizontal - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Maximum channel pulse width</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html> - - - 2000 - - - - - - - Check this to reverse the channel. -(Useful for transmitters without channel -reversal capabilities). - - - - - - - - - - - - - true - - - 1000 - - - 2000 - - - 1500 - - - Qt::Horizontal - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Maximum channel pulse width</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html> - - - 2000 - - - - - - - Check this to reverse the channel. -(Useful for transmitters without channel -reversal capabilities). - - - - - - - - - - - - - true - - - 1000 - - - 2000 - - - 1500 - - - Qt::Horizontal - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Maximum channel pulse width</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html> - - - 2000 - - - - - - - Check this to reverse the channel. -(Useful for transmitters without channel -reversal capabilities). - - - - - - - - - - - - - true - - - 1000 - - - 2000 - - - 1500 - - - Qt::Horizontal - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Maximum channel pulse width</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html> - - - 2000 - - - - - - - Check this to reverse the channel. -(Useful for transmitters without channel -reversal capabilities). - - - - - - - - - - - - - true - - - 1000 - - - 2000 - - - 1500 - - - Qt::Horizontal - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Maximum channel pulse width</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html> - - - 2000 - - - - - - - Check this to reverse the channel. -(Useful for transmitters without channel -reversal capabilities). - - - - - - - - - - - - - true - - - 1000 - - - 2000 - - - 1500 - - - Qt::Horizontal - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Maximum channel pulse width</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html> - - - 2000 - - - - - - - Check this to reverse the channel. -(Useful for transmitters without channel -reversal capabilities). - - - - - - - - - - - 75 - true - - - - BEWARE: make sure your engines are not connected when running calibration! - - - - - - - - - 75 - true - - - - - - - - - - - - 50 - false - - - - Start calibrating the RC Inputs. -Uncheck/Check to restart calibration. -During calibration: move your RC controls over their whole range, -then leave them on Neutral, uncheck calibration and save. -Neutral should be put at the bottom of the slider for the throttle. - - - Run Calibration - - - - - - - - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Minimum channel pulse width</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html> - - - 1000 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Minimum channel pulse width</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html> - - - 1000 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Minimum channel pulse width</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html> - - - 1000 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Minimum channel pulse width</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html> - - - 1000 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Minimum channel pulse width</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html> - - - 1000 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Minimum channel pulse width</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html> - - - 1000 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Minimum channel pulse width</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html> - - - 1000 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Minimum channel pulse width</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html> - - - 1000 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:10pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:9pt;">Current channel value.</span></p></body></html> - - - 1500 - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:10pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:9pt;">Current channel value.</span></p></body></html> - - - 1500 - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:10pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:9pt;">Current channel value.</span></p></body></html> - - - 1500 - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:10pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:9pt;">Current channel value.</span></p></body></html> - - - 1500 - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:10pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:9pt;">Current channel value.</span></p></body></html> - - - 1500 - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:10pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:9pt;">Current channel value.</span></p></body></html> - - - 1500 - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:10pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:9pt;">Current channel value.</span></p></body></html> - - - 1500 - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:10pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:9pt;">Current channel value.</span></p></body></html> - - - 1500 - + + + 1 + + + + + + + + + + + 0 + 0 + + + + + 0 + 70 + + + + + 10 + 75 + true + + + + TextLabel + + + true + + + + + + + + + + + + + + + + + + + Back + + + + + + + Next + + + + + + + Cancel + + + + + + + @@ -1243,14 +554,6 @@ Applies and Saves all settings to SD - ch0Assign - ch1Assign - ch2Assign - ch3Assign - ch4Assign - ch5Assign - ch6Assign - ch7Assign fmsSlider fmsModePos3 fmsSsPos3Roll @@ -1268,134 +571,5 @@ Applies and Saves all settings to SD - - - inSlider0 - valueChanged(int) - ch0Cur - setNum(int) - - - 291 - 93 - - - 150 - 104 - - - - - inSlider1 - valueChanged(int) - ch1Cur - setNum(int) - - - 283 - 137 - - - 160 - 138 - - - - - inSlider2 - valueChanged(int) - ch2Cur - setNum(int) - - - 341 - 163 - - - 156 - 167 - - - - - inSlider3 - valueChanged(int) - ch3Cur - setNum(int) - - - 283 - 211 - - - 159 - 210 - - - - - inSlider4 - valueChanged(int) - ch4Cur - setNum(int) - - - 287 - 239 - - - 156 - 242 - - - - - inSlider5 - valueChanged(int) - ch5Cur - setNum(int) - - - 309 - 272 - - - 164 - 276 - - - - - inSlider6 - valueChanged(int) - ch6Cur - setNum(int) - - - 282 - 300 - - - 144 - 311 - - - - - inSlider7 - valueChanged(int) - ch7Cur - setNum(int) - - - 278 - 339 - - - 168 - 340 - - - - + diff --git a/ground/openpilotgcs/src/plugins/config/inputchannelform.cpp b/ground/openpilotgcs/src/plugins/config/inputchannelform.cpp new file mode 100644 index 000000000..904918a8e --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/inputchannelform.cpp @@ -0,0 +1,29 @@ +#include "inputchannelform.h" +#include "ui_inputchannelform.h" + +inputChannelForm::inputChannelForm(QWidget *parent,bool showlegend) : + QWidget(parent), + ui(new Ui::inputChannelForm) +{ + ui->setupUi(this); + if(!showlegend) + { + layout()->removeWidget(ui->legend0); + layout()->removeWidget(ui->legend1); + layout()->removeWidget(ui->legend2); + layout()->removeWidget(ui->legend3); + layout()->removeWidget(ui->legend4); + layout()->removeWidget(ui->legend5); + delete ui->legend0; + delete ui->legend1; + delete ui->legend2; + delete ui->legend3; + delete ui->legend4; + delete ui->legend5; + } +} + +inputChannelForm::~inputChannelForm() +{ + delete ui; +} diff --git a/ground/openpilotgcs/src/plugins/config/inputchannelform.h b/ground/openpilotgcs/src/plugins/config/inputchannelform.h new file mode 100644 index 000000000..50615cb2c --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/inputchannelform.h @@ -0,0 +1,23 @@ +#ifndef INPUTCHANNELFORM_H +#define INPUTCHANNELFORM_H + +#include +#include "configinputwidget.h" +namespace Ui { + class inputChannelForm; +} + +class inputChannelForm : public QWidget +{ + Q_OBJECT + +public: + explicit inputChannelForm(QWidget *parent = 0,bool showlegend=false); + ~inputChannelForm(); + friend class ConfigInputWidget; + +private: + Ui::inputChannelForm *ui; +}; + +#endif // INPUTCHANNELFORM_H diff --git a/ground/openpilotgcs/src/plugins/config/inputchannelform.ui b/ground/openpilotgcs/src/plugins/config/inputchannelform.ui new file mode 100644 index 000000000..ac4c9e015 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/inputchannelform.ui @@ -0,0 +1,143 @@ + + + inputChannelForm + + + + 0 + 0 + 404 + 43 + + + + Form + + + + 1 + + + 1 + + + 2 + + + 0 + + + + + true + + + Number + + + + + + + true + + + Min + + + + + + + true + + + Function + + + + + + + true + + + Group + + + + + + + + 0 + 0 + + + + + 70 + 0 + + + + TextLabel + + + + + + + + + + 255 + + + + + + + true + + + Neutral + + + + + + + 9999 + + + + + + + 9999 + + + + + + + true + + + Max + + + + + + + 9999 + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/config/smartsavebutton.cpp b/ground/openpilotgcs/src/plugins/config/smartsavebutton.cpp index ed5abf2c7..c74f22691 100644 --- a/ground/openpilotgcs/src/plugins/config/smartsavebutton.cpp +++ b/ground/openpilotgcs/src/plugins/config/smartsavebutton.cpp @@ -24,8 +24,11 @@ void smartSaveButton::processClick() bool error=false; ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); UAVObjectUtilManager* utilMngr = pm->getObject(); - foreach(UAVObject * obj,objects) + foreach(UAVDataObject * obj,objects) { + UAVObject::Metadata mdata= obj->getMetadata(); + if(mdata.gcsAccess==UAVObject::ACCESS_READONLY) + continue; up_result=false; current_object=obj; for(int i=0;i<3;++i) @@ -35,7 +38,9 @@ void smartSaveButton::processClick() connect(&timer,SIGNAL(timeout()),&loop,SLOT(quit())); obj->updated(); timer.start(1000); + //qDebug()<<"begin loop"; loop.exec(); + //qDebug()<<"end loop"; timer.stop(); disconnect(obj,SIGNAL(transactionCompleted(UAVObject*,bool)),this,SLOT(transaction_finished(UAVObject*, bool))); disconnect(&timer,SIGNAL(timeout()),&loop,SLOT(quit())); @@ -44,30 +49,32 @@ void smartSaveButton::processClick() } if(up_result==false) { + //qDebug()<<"Object upload error:"<getName(); error=true; continue; } sv_result=false; current_objectID=obj->getObjID(); - if(save) + if(save && (obj->isSettings())) { - for(int i=0;i<3;++i) - { - connect(utilMngr,SIGNAL(saveCompleted(int,bool)),this,SLOT(saving_finished(int,bool))); - connect(&timer,SIGNAL(timeout()),&loop,SLOT(quit())); - utilMngr->saveObjectToSD(obj); - timer.start(1000); - loop.exec(); - timer.stop(); - disconnect(utilMngr,SIGNAL(saveCompleted(int,bool)),this,SLOT(saving_finished(int,bool))); - disconnect(&timer,SIGNAL(timeout()),&loop,SLOT(quit())); - if(sv_result) - break; - } - if(sv_result==false) - { - error=true; - } + for(int i=0;i<3;++i) + { + //qDebug()<<"try to save:"<getName(); + connect(utilMngr,SIGNAL(saveCompleted(int,bool)),this,SLOT(saving_finished(int,bool))); + connect(&timer,SIGNAL(timeout()),&loop,SLOT(quit())); + utilMngr->saveObjectToSD(obj); + timer.start(1000); + loop.exec(); + timer.stop(); + disconnect(utilMngr,SIGNAL(saveCompleted(int,bool)),this,SLOT(saving_finished(int,bool))); + disconnect(&timer,SIGNAL(timeout()),&loop,SLOT(quit())); + if(sv_result) + break; + } + if(sv_result==false) + { + error=true; + } } } button->setEnabled(true); @@ -83,14 +90,15 @@ void smartSaveButton::processClick() emit endOp(); } -void smartSaveButton::setObjects(QList list) +void smartSaveButton::setObjects(QList list) { objects=list; } -void smartSaveButton::addObject(UAVObject * obj) +void smartSaveButton::addObject(UAVDataObject * obj) { - objects.append(obj); + if(!objects.contains(obj)) + objects.append(obj); } void smartSaveButton::clearObjects() @@ -111,6 +119,7 @@ void smartSaveButton::saving_finished(int id, bool result) if(id==current_objectID) { sv_result=result; + //qDebug()<<"saving_finished result="<); - void addObject(UAVObject *); + void setObjects(QList); + void addObject(UAVDataObject *); void clearObjects(); signals: void preProcessOperations(); @@ -34,11 +34,11 @@ private: QPushButton *bupdate; QPushButton *bsave; quint32 current_objectID; - UAVObject * current_object; + UAVDataObject * current_object; bool up_result; bool sv_result; QEventLoop loop; - QList objects; + QList objects; protected: public slots: void enableControls(bool value); diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index 96c414055..5c2de727e 100644 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -6,649 +6,689 @@ 0 0 - 639 - 611 + 683 + 685 Form - + - + - + 0 - 0 + 1 - - - 0 - 150 - + + QFrame::NoFrame - - Rate Stabilization Coefficients (Inner Loop) + + true - - - - - Kp - - - Qt::AlignCenter - - - - - - - Ki - - - Qt::AlignCenter - - - - - - - ILimit - - - Qt::AlignCenter - - - - - - - Roll - - - - - - - Slowly raise Kp until you start seeing clear oscillations when you fly. + + + + 0 + 0 + 665 + 627 + + + + + 0 + 0 + + + + + 0 + + + 0 + + + + + + 0 + 0 + + + + + 0 + 150 + + + + Rate Stabilization Coefficients (Inner Loop) + + + + + + Kp + + + Qt::AlignCenter + + + + + + + Ki + + + Qt::AlignCenter + + + + + + + ILimit + + + Qt::AlignCenter + + + + + + + Roll + + + + + + + Slowly raise Kp until you start seeing clear oscillations when you fly. Then lower the value by 20% or so. - - - 6 - - - 0.000100000000000 - - - - - - - I factor for rate stabilization is usually very low or even zero. - - - 6 - - - 0.000100000000000 - - - - - - - 6 - - - 0.000100000000000 - - - - - - - If checked, the Roll and Pitch factors will be identical. + + + 6 + + + 0.000100000000000 + + + + + + + I factor for rate stabilization is usually very low or even zero. + + + 6 + + + 0.000100000000000 + + + + + + + 6 + + + 0.000100000000000 + + + + + + + If checked, the Roll and Pitch factors will be identical. When you change one, the other is updated. - - - Link - - - - - - - Pitch - - - - - - - Slowly raise Kp until you start seeing clear oscillations when you fly. + + + Link + + + + + + + Pitch + + + + + + + Slowly raise Kp until you start seeing clear oscillations when you fly. Then lower the value by 20% or so. - - - 6 - - - 0.000100000000000 - - - - - - - I factor for rate stabilization is usually very low or even zero. - - - 6 - - - 0.000100000000000 - - - - - - - 6 - - - 0.000100000000000 - - - - - - - Yaw - - - - - - - Slowly raise Kp until you start seeing clear oscillations when you fly. + + + 6 + + + 0.000100000000000 + + + + + + + I factor for rate stabilization is usually very low or even zero. + + + 6 + + + 0.000100000000000 + + + + + + + 6 + + + 0.000100000000000 + + + + + + + Yaw + + + + + + + Slowly raise Kp until you start seeing clear oscillations when you fly. Then lower the value by 20% or so. You can usually go for higher values for Yaw factors. - - - 6 - - - 0.000100000000000 - - - - - - - As a rule of thumb, you can set YawRate Ki at roughly the same + + + 6 + + + 0.000100000000000 + + + + + + + As a rule of thumb, you can set YawRate Ki at roughly the same value as YawRate Kp. - - - 6 - - - 0.000100000000000 - - - - - - - 6 - - - 0.000100000000000 - - - - - - - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 20 - 5 - - - - - - - - - 0 - 0 - - - - - 0 - 150 - - - - Attitude Stabization Coefficients (Outer Loop) - - - - - - Once Rate stabilization is done, you should increase the Kp factor until the airframe oscillates again, and go back down 20% or so. + + + 6 + + + 0.000100000000000 + + + + + + + 6 + + + 0.000100000000000 + + + + + + + + + + Qt::Vertical + + + QSizePolicy::Fixed + + + + 20 + 13 + + + + + + + + + 0 + 0 + + + + + 0 + 150 + + + + Attitude Stabization Coefficients (Outer Loop) + + + + + + Once Rate stabilization is done, you should increase the Kp factor until the airframe oscillates again, and go back down 20% or so. - - - 6 - - - 0.100000000000000 - - - - - - - Ki can usually be almost identical to Kp. - - - 6 - - - 0.100000000000000 - - - - - - - ILimit can be equal to three to four times Ki, but you can adjust + + + 6 + + + 0.100000000000000 + + + + + + + Ki can usually be almost identical to Kp. + + + 6 + + + 0.100000000000000 + + + + + + + ILimit can be equal to three to four times Ki, but you can adjust depending on whether your airframe is well balanced, and your flying style. - - - 6 - - - 0.100000000000000 - - - - - - - Kp - - - Qt::AlignCenter - - - - - - - Ki - - - Qt::AlignCenter - - - - - - - ILimit - - - Qt::AlignCenter - - - - - - - ILimit can be equal to three to four times Ki, but you can adjust + + + 6 + + + 0.100000000000000 + + + + + + + Kp + + + Qt::AlignCenter + + + + + + + Ki + + + Qt::AlignCenter + + + + + + + ILimit + + + Qt::AlignCenter + + + + + + + ILimit can be equal to three to four times Ki, but you can adjust depending on whether your airframe is well balanced, and your flying style. - - - 6 - - - 0.100000000000000 - - - - - - - Ki can usually be almost identical to Kp. - - - 6 - - - 0.100000000000000 - - - - - - - Once Rate stabilization is done, you should increase the Kp factor until the airframe oscillates again, and go back down 20% or so. + + + 6 + + + 0.100000000000000 + + + + + + + Ki can usually be almost identical to Kp. + + + 6 + + + 0.100000000000000 + + + + + + + Once Rate stabilization is done, you should increase the Kp factor until the airframe oscillates again, and go back down 20% or so. - - - 6 - - - 0.100000000000000 - - - - - - - Once Rate stabilization is done, you should increase the Kp factor until the airframe oscillates again, and go back down 20% or so. + + + 6 + + + 0.100000000000000 + + + + + + + Once Rate stabilization is done, you should increase the Kp factor until the airframe oscillates again, and go back down 20% or so. - - - 6 - - - 0.100000000000000 - - - - - - - Yaw - - - - - - - Pitch - - - - - - - Roll - - - - - - - Ki can usually be almost identical to Kp. - - - 6 - - - 0.100000000000000 - - - - - - - ILimit can be equal to three to four times Ki, but you can adjust + + + 6 + + + 0.100000000000000 + + + + + + + Yaw + + + + + + + Pitch + + + + + + + Roll + + + + + + + Ki can usually be almost identical to Kp. + + + 6 + + + 0.100000000000000 + + + + + + + ILimit can be equal to three to four times Ki, but you can adjust depending on whether your airframe is well balanced, and your flying style. - - - 6 - - - 0.100000000000000 - - - - - - - If checked, the Roll and Pitch factors will be identical. + + + 6 + + + 0.100000000000000 + + + + + + + If checked, the Roll and Pitch factors will be identical. When you change one, the other is updated. - - - Link - - - - + + + Link + + + + + + + + + + Qt::Vertical + + + QSizePolicy::Fixed + + + + 20 + 13 + + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + Stick range and limits + + + + QLayout::SetMinAndMaxSize + + + + + Roll + + + Qt::AlignCenter + + + + + + + Pitch + + + Qt::AlignCenter + + + + + + + Yaw + + + Qt::AlignCenter + + + + + + + 180 + + + + + + + 180 + + + + + + + 180 + + + + + + + + 150 + 0 + + + + + 50 + false + + + + Full stick angle (deg) + + + + + + + + 150 + 0 + + + + + 50 + false + + + + Full stick rate (deg/s) + + + + + + + 500 + + + + + + + 500 + + + + + + + 500 + + + + + + + + 150 + 0 + + + + + 50 + false + + + + + + + Maximum rate in attitude mode (deg/s) + + + + + + + 500 + + + + + + + 500 + + + + + + + 500 + + + + + + + + + + Zero the integral when throttle is low + + + + + + + Qt::Vertical + + + + 20 + 0 + + + + + + - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 20 - 5 - - - - - - - - - 0 - 0 - - - - - 0 - 0 - - - - Stick range and limits - - - - QLayout::SetMinAndMaxSize - - - - - Roll - - - Qt::AlignCenter - - - - - - - Pitch - - - Qt::AlignCenter - - - - - - - Yaw - - - Qt::AlignCenter - - - - - - - 180 - - - - - - - 180 - - - - - - - 180 - - - - - - - - 150 - 0 - - - - - 50 - false - - - - Full stick angle (deg) - - - - - - - - 150 - 0 - - - - - 50 - false - - - - Full stick rate (deg/s) - - - - - - - 300 - - - - - - - 300 - - - - - - - 300 - - - - - - - - 150 - 0 - - - - - 50 - false - - - - - - - Maximum rate in attitude mode (deg/s) - - - - - - - 300 - - - - - - - 300 - - - - - - - 300 - - - - - - - - - - Zero the integral when throttle is low - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - diff --git a/ground/openpilotgcs/src/plugins/pfd/pfdgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/pfd/pfdgadgetwidget.cpp index 079a206b5..a38e943a3 100644 --- a/ground/openpilotgcs/src/plugins/pfd/pfdgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/pfd/pfdgadgetwidget.cpp @@ -27,6 +27,7 @@ #include "pfdgadgetwidget.h" #include +#include #include #include #include @@ -383,7 +384,7 @@ void PFDGadgetWidget::setDialFile(QString dfn) - Battery stats: battery-txt */ l_scene->clear(); // Deletes all items contained in the scene as well. - m_background = new QGraphicsSvgItem(); + m_background = new CachedSvgItem(); // All other items will be clipped to the shape of the background m_background->setFlags(QGraphicsItem::ItemClipsChildrenToShape| QGraphicsItem::ItemClipsToShape); @@ -391,28 +392,28 @@ void PFDGadgetWidget::setDialFile(QString dfn) m_background->setElementId("background"); l_scene->addItem(m_background); - m_world = new QGraphicsSvgItem(); + m_world = new CachedSvgItem(); m_world->setParentItem(m_background); m_world->setSharedRenderer(m_renderer); m_world->setElementId("world"); l_scene->addItem(m_world); // red Roll scale: rollscale - m_rollscale = new QGraphicsSvgItem(); + m_rollscale = new CachedSvgItem(); m_rollscale->setSharedRenderer(m_renderer); m_rollscale->setElementId("rollscale"); l_scene->addItem(m_rollscale); // Home point: - m_homewaypoint = new QGraphicsSvgItem(); + m_homewaypoint = new CachedSvgItem(); // Next point: - m_nextwaypoint = new QGraphicsSvgItem(); + m_nextwaypoint = new CachedSvgItem(); // Home point bearing: - m_homepointbearing = new QGraphicsSvgItem(); + m_homepointbearing = new CachedSvgItem(); // Next point bearing: - m_nextpointbearing = new QGraphicsSvgItem(); + m_nextpointbearing = new CachedSvgItem(); - QGraphicsSvgItem *m_foreground = new QGraphicsSvgItem(); + QGraphicsSvgItem *m_foreground = new CachedSvgItem(); m_foreground->setParentItem(m_background); m_foreground->setSharedRenderer(m_renderer); m_foreground->setElementId("foreground"); @@ -429,7 +430,7 @@ void PFDGadgetWidget::setDialFile(QString dfn) // into a QGraphicsSvgItem which we will display at the same // place: we do this so that the heading scale can be clipped to // the compass dial region. - m_compass = new QGraphicsSvgItem(); + m_compass = new CachedSvgItem(); m_compass->setSharedRenderer(m_renderer); m_compass->setElementId("compass"); m_compass->setFlags(QGraphicsItem::ItemClipsChildrenToShape| @@ -440,7 +441,7 @@ void PFDGadgetWidget::setDialFile(QString dfn) m_compass->setTransform(matrix,false); // Now place the compass scale inside: - m_compassband = new QGraphicsSvgItem(); + m_compassband = new CachedSvgItem(); m_compassband->setSharedRenderer(m_renderer); m_compassband->setElementId("compass-band"); m_compassband->setParentItem(m_compass); @@ -462,7 +463,7 @@ void PFDGadgetWidget::setDialFile(QString dfn) compassMatrix = m_renderer->matrixForElement("speed-bg"); startX = compassMatrix.mapRect(m_renderer->boundsOnElement("speed-bg")).x(); startY = compassMatrix.mapRect(m_renderer->boundsOnElement("speed-bg")).y(); - QGraphicsSvgItem *verticalbg = new QGraphicsSvgItem(); + QGraphicsSvgItem *verticalbg = new CachedSvgItem(); verticalbg->setSharedRenderer(m_renderer); verticalbg->setElementId("speed-bg"); verticalbg->setFlags(QGraphicsItem::ItemClipsChildrenToShape| @@ -477,7 +478,7 @@ void PFDGadgetWidget::setDialFile(QString dfn) m_speedscale = new QGraphicsItemGroup(); m_speedscale->setParentItem(verticalbg); - QGraphicsSvgItem *speedscalelines = new QGraphicsSvgItem(); + QGraphicsSvgItem *speedscalelines = new CachedSvgItem(); speedscalelines->setSharedRenderer(m_renderer); speedscalelines->setElementId("speed-scale"); speedScaleHeight = m_renderer->matrixForElement("speed-scale").mapRect( @@ -523,7 +524,7 @@ void PFDGadgetWidget::setDialFile(QString dfn) startX = compassMatrix.mapRect(m_renderer->boundsOnElement("speed-window")).x(); startY = compassMatrix.mapRect(m_renderer->boundsOnElement("speed-window")).y(); qreal speedWindowHeight = compassMatrix.mapRect(m_renderer->boundsOnElement("speed-window")).height(); - QGraphicsSvgItem *speedwindow = new QGraphicsSvgItem(); + QGraphicsSvgItem *speedwindow = new CachedSvgItem(); speedwindow->setSharedRenderer(m_renderer); speedwindow->setElementId("speed-window"); speedwindow->setFlags(QGraphicsItem::ItemClipsChildrenToShape| @@ -548,7 +549,7 @@ void PFDGadgetWidget::setDialFile(QString dfn) compassMatrix = m_renderer->matrixForElement("altitude-bg"); startX = compassMatrix.mapRect(m_renderer->boundsOnElement("altitude-bg")).x(); startY = compassMatrix.mapRect(m_renderer->boundsOnElement("altitude-bg")).y(); - verticalbg = new QGraphicsSvgItem(); + verticalbg = new CachedSvgItem(); verticalbg->setSharedRenderer(m_renderer); verticalbg->setElementId("altitude-bg"); verticalbg->setFlags(QGraphicsItem::ItemClipsChildrenToShape| @@ -563,7 +564,7 @@ void PFDGadgetWidget::setDialFile(QString dfn) m_altitudescale = new QGraphicsItemGroup(); m_altitudescale->setParentItem(verticalbg); - QGraphicsSvgItem *altitudescalelines = new QGraphicsSvgItem(); + QGraphicsSvgItem *altitudescalelines = new CachedSvgItem(); altitudescalelines->setSharedRenderer(m_renderer); altitudescalelines->setElementId("altitude-scale"); altitudeScaleHeight = m_renderer->matrixForElement("altitude-scale").mapRect( @@ -604,7 +605,7 @@ void PFDGadgetWidget::setDialFile(QString dfn) startX = compassMatrix.mapRect(m_renderer->boundsOnElement("altitude-window")).x(); startY = compassMatrix.mapRect(m_renderer->boundsOnElement("altitude-window")).y(); qreal altitudeWindowHeight = compassMatrix.mapRect(m_renderer->boundsOnElement("altitude-window")).height(); - QGraphicsSvgItem *altitudewindow = new QGraphicsSvgItem(); + QGraphicsSvgItem *altitudewindow = new CachedSvgItem(); altitudewindow->setSharedRenderer(m_renderer); altitudewindow->setElementId("altitude-window"); altitudewindow->setFlags(QGraphicsItem::ItemClipsChildrenToShape| @@ -633,7 +634,7 @@ void PFDGadgetWidget::setDialFile(QString dfn) compassMatrix = m_renderer->matrixForElement("gcstelemetry-Disconnected"); startX = compassMatrix.mapRect(m_renderer->boundsOnElement("gcstelemetry-Disconnected")).x(); startY = compassMatrix.mapRect(m_renderer->boundsOnElement("gcstelemetry-Disconnected")).y(); - gcsTelemetryArrow = new QGraphicsSvgItem(); + gcsTelemetryArrow = new CachedSvgItem(); gcsTelemetryArrow->setSharedRenderer(m_renderer); gcsTelemetryArrow->setElementId("gcstelemetry-Disconnected"); l_scene->addItem(gcsTelemetryArrow); @@ -669,7 +670,7 @@ void PFDGadgetWidget::setDialFile(QString dfn) compassMatrix = m_renderer->matrixForElement("gcstelemetry-Disconnected"); startX = compassMatrix.mapRect(m_renderer->boundsOnElement("gcstelemetry-Disconnected")).x(); startY = compassMatrix.mapRect(m_renderer->boundsOnElement("gcstelemetry-Disconnected")).y(); - gcsTelemetryArrow = new QGraphicsSvgItem(); + gcsTelemetryArrow = new CachedSvgItem(); gcsTelemetryArrow->setSharedRenderer(m_renderer); gcsTelemetryArrow->setElementId("gcstelemetry-Disconnected"); l_scene->addItem(gcsTelemetryArrow); @@ -702,7 +703,7 @@ void PFDGadgetWidget::setDialFile(QString dfn) compassMatrix = m_renderer->matrixForElement("gcstelemetry-Disconnected"); startX = compassMatrix.mapRect(m_renderer->boundsOnElement("gcstelemetry-Disconnected")).x(); startY = compassMatrix.mapRect(m_renderer->boundsOnElement("gcstelemetry-Disconnected")).y(); - gcsTelemetryArrow = new QGraphicsSvgItem(); + gcsTelemetryArrow = new CachedSvgItem(); gcsTelemetryArrow->setSharedRenderer(m_renderer); gcsTelemetryArrow->setElementId("gcstelemetry-Disconnected"); l_scene->addItem(gcsTelemetryArrow); @@ -771,7 +772,7 @@ void PFDGadgetWidget::setDialFile(QString dfn) { qDebug()<<"Error on PFD artwork file."; m_renderer->load(QString(":/pfd/images/pfd-default.svg")); l_scene->clear(); // This also deletes all items contained in the scene. - m_background = new QGraphicsSvgItem(); + m_background = new CachedSvgItem(); m_background->setSharedRenderer(m_renderer); l_scene->addItem(m_background); pfdError = true; diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro index 968991a94..fdd57753d 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro @@ -69,6 +69,8 @@ HEADERS += $$UAVOBJECT_SYNTHETICS/accessorydesired.h \ $$UAVOBJECT_SYNTHETICS/sonaraltitude.h \ $$UAVOBJECT_SYNTHETICS/flightstatus.h \ $$UAVOBJECT_SYNTHETICS/hwsettings.h \ + $$UAVOBJECT_SYNTHETICS/gcsreceiver.h \ + $$UAVOBJECT_SYNTHETICS/receiveractivity.h \ $$UAVOBJECT_SYNTHETICS/attitudesettings.h \ $$UAVOBJECT_SYNTHETICS/cameradesired.h @@ -119,5 +121,7 @@ SOURCES += $$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \ $$UAVOBJECT_SYNTHETICS/uavobjectsinit.cpp \ $$UAVOBJECT_SYNTHETICS/flightstatus.cpp \ $$UAVOBJECT_SYNTHETICS/hwsettings.cpp \ + $$UAVOBJECT_SYNTHETICS/gcsreceiver.cpp \ + $$UAVOBJECT_SYNTHETICS/receiveractivity.cpp \ $$UAVOBJECT_SYNTHETICS/attitudesettings.cpp \ $$UAVOBJECT_SYNTHETICS/cameradesired.cpp diff --git a/ground/openpilotgcs/src/plugins/uploader/devicewidget.cpp b/ground/openpilotgcs/src/plugins/uploader/devicewidget.cpp index e2300bdcd..6ef7850e0 100644 --- a/ground/openpilotgcs/src/plugins/uploader/devicewidget.cpp +++ b/ground/openpilotgcs/src/plugins/uploader/devicewidget.cpp @@ -303,7 +303,10 @@ void deviceWidget::loadFirmware() myDevice->youdont->setChecked(false); QByteArray desc = loadedFW.right(100); QPixmap px; - myDevice->lblCRCL->setText( QString::number(DFUObject::CRCFromQBArray(loadedFW,m_dfu->devices[deviceID].SizeOfCode))); + if(loadedFW.length()>m_dfu->devices[deviceID].SizeOfCode) + myDevice->lblCRCL->setText(tr("Can't calculate, file too big for device")); + else + myDevice->lblCRCL->setText( QString::number(DFUObject::CRCFromQBArray(loadedFW,m_dfu->devices[deviceID].SizeOfCode))); //myDevice->lblFirmwareSizeL->setText(QString("Firmware size: ")+QVariant(loadedFW.length()).toString()+ QString(" bytes")); if (populateLoadedStructuredDescription(desc)) { diff --git a/ground/openpilotgcs/src/plugins/uploader/op_dfu.cpp b/ground/openpilotgcs/src/plugins/uploader/op_dfu.cpp index 8a9045233..b1e215f91 100644 --- a/ground/openpilotgcs/src/plugins/uploader/op_dfu.cpp +++ b/ground/openpilotgcs/src/plugins/uploader/op_dfu.cpp @@ -956,7 +956,7 @@ quint32 DFUObject::CRC32WideFast(quint32 Crc, quint32 Size, quint32 *Buffer) */ quint32 DFUObject::CRCFromQBArray(QByteArray array, quint32 Size) { - int pad=Size-array.length(); + quint32 pad=Size-array.length(); array.append(QByteArray(pad,255)); quint32 t[Size/4]; for(int x=0;x + + A receiver channel group carried over the telemetry link. + + + + + + + diff --git a/shared/uavobjectdefinition/hwsettings.xml b/shared/uavobjectdefinition/hwsettings.xml index 63c2a745a..242cba679 100644 --- a/shared/uavobjectdefinition/hwsettings.xml +++ b/shared/uavobjectdefinition/hwsettings.xml @@ -1,9 +1,18 @@ Selection of optional hardware configurations. - - + + + + + + + + + + + diff --git a/shared/uavobjectdefinition/manualcontrolsettings.xml b/shared/uavobjectdefinition/manualcontrolsettings.xml index bfd692f91..d6d7b90a3 100644 --- a/shared/uavobjectdefinition/manualcontrolsettings.xml +++ b/shared/uavobjectdefinition/manualcontrolsettings.xml @@ -1,15 +1,18 @@ Settings to indicate how to decode receiver input by @ref ManualControlModule. - - - - - - - - - + + + + + + @@ -20,9 +23,6 @@ - - - diff --git a/shared/uavobjectdefinition/receiveractivity.xml b/shared/uavobjectdefinition/receiveractivity.xml new file mode 100644 index 000000000..2e98c1362 --- /dev/null +++ b/shared/uavobjectdefinition/receiveractivity.xml @@ -0,0 +1,14 @@ + + + Monitors which receiver channels have been active within the last second. + + + + + + + + diff --git a/shared/uavobjectdefinition/stabilizationsettings.xml b/shared/uavobjectdefinition/stabilizationsettings.xml index 653c7cce8..e42f468bf 100644 --- a/shared/uavobjectdefinition/stabilizationsettings.xml +++ b/shared/uavobjectdefinition/stabilizationsettings.xml @@ -1,8 +1,8 @@ PID settings used by the Stabilization module to combine the @ref AttitudeActual and @ref AttitudeDesired to compute @ref ActuatorDesired - - + +