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

Merge branch 'next' of ssh://git.openpilot.org/OpenPilot into next

This commit is contained in:
dankers 2011-08-13 06:12:08 +10:00
commit 69f8aac967
169 changed files with 7260 additions and 3110 deletions

View File

@ -1,21 +1,30 @@
Short summary of changes. For a complete list see the git log.
2011-07-17
Updated module initialization from Mathieu which separates the initialization
from the task startup. Also implements a method to reclaim unused ram from
initialization and end of memory for the FreeRTOS heap.
2011-07-12
Improvements to the stabilization code. Included a LPF on the gyros to smooth
out noise in high vibration environments. Also two new modes: axis-lock and
weak leveling. Axis-lock will try and hold an axis at a fixed position and
reject any disturbances. This is like heading-hold on a heli for the tail but
can be useful for other axes. Weak leveling is rate mode with a weak
correction to self level the craft - good for easier rate mode flying.
2011-07-07
Dynamic hardware configuration from Stac. The input type is now
selected from ManualControlSettings.InputMode and the aircraft must be rebooted
after changing this. Also for CopterControl the HwSettings object must
indicate which modules are connected to which ports. PPM currently not
working.
Short summary of changes. For a complete list see the git log.
2011-08-04
Fixed packaging aesthetic issues. Also avoid runtime issues on OSX Lion by
disabling the ModelView and Notify plugins for now (sorry).
2011-07-29
Added support for PPM receivers from James W. Now all 4 interfaces (R/C
standard PWM, combined PPM (MK), Spektrum satellite, Futaba S.Bus) are
supported and configurable through the GCS hardware configuration tab.
2011-07-17
Updated module initialization from Mathieu which separates the initialization
from the task startup. Also implements a method to reclaim unused ram from
initialization and end of memory for the FreeRTOS heap.
2011-07-12
Improvements to the stabilization code. Included a LPF on the gyros to smooth
out noise in high vibration environments. Also two new modes: axis-lock and
weak leveling. Axis-lock will try and hold an axis at a fixed position and
reject any disturbances. This is like heading-hold on a heli for the tail but
can be useful for other axes. Weak leveling is rate mode with a weak
correction to self level the craft - good for easier rate mode flying.
2011-07-07
Dynamic hardware configuration from Stac. The input type is now
selected from ManualControlSettings.InputMode and the aircraft must be rebooted
after changing this. Also for CopterControl the HwSettings object must
indicate which modules are connected to which ports. PPM currently not
working.

View File

@ -54,7 +54,6 @@ static const struct pios_spi_cfg pios_spi_op_cfg = {
.ahb_clk = RCC_AHBPeriph_DMA1,
.irq = {
.handler = NULL,
.flags =
(DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 |
DMA1_FLAG_GL4),
@ -157,7 +156,6 @@ static const struct pios_adc_cfg pios_adc_cfg = {
.dma = {
.ahb_clk = RCC_AHBPeriph_DMA1,
.irq = {
.handler = NULL,
.flags = (DMA1_FLAG_TC1 | DMA1_FLAG_TE1 | DMA1_FLAG_HT1 | DMA1_FLAG_GL1),
.init = {
.NVIC_IRQChannel = DMA1_Channel1_IRQn,
@ -217,7 +215,6 @@ static const struct pios_usart_cfg pios_usart_aux_cfg = {
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
},
.irq = {
.handler = NULL,
.init = {
.NVIC_IRQChannel = USART3_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
@ -249,6 +246,9 @@ static const struct pios_usart_cfg pios_usart_aux_cfg = {
#include <pios_com_priv.h>
#define PIOS_COM_AUX_TX_BUF_LEN 192
static uint8_t pios_com_aux_tx_buffer[PIOS_COM_AUX_TX_BUF_LEN];
#endif /* PIOS_INCLUDE_COM */
#if defined(PIOS_INCLUDE_I2C)
@ -294,7 +294,6 @@ static const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = {
},
},
.event = {
.handler = NULL,
.flags = 0, /* FIXME: check this */
.init = {
.NVIC_IRQChannel = I2C1_EV_IRQn,
@ -304,7 +303,6 @@ static const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = {
},
},
.error = {
.handler = NULL,
.flags = 0, /* FIXME: check this */
.init = {
.NVIC_IRQChannel = I2C1_ER_IRQn,
@ -375,12 +373,16 @@ void PIOS_Board_Init(void) {
/* Communication system */
#if !defined(PIOS_ENABLE_DEBUG_PINS)
#if defined(PIOS_INCLUDE_COM)
uint32_t pios_usart_aux_id;
if (PIOS_USART_Init(&pios_usart_aux_id, &pios_usart_aux_cfg)) {
PIOS_DEBUG_Assert(0);
}
if (PIOS_COM_Init(&pios_com_aux_id, &pios_usart_com_driver, pios_usart_aux_id)) {
PIOS_DEBUG_Assert(0);
{
uint32_t pios_usart_aux_id;
if (PIOS_USART_Init(&pios_usart_aux_id, &pios_usart_aux_cfg)) {
PIOS_DEBUG_Assert(0);
}
if (PIOS_COM_Init(&pios_com_aux_id, &pios_usart_com_driver, pios_usart_aux_id,
NULL, 0,
pios_com_aux_tx_buffer, sizeof(pios_com_aux_tx_buffer))) {
PIOS_DEBUG_Assert(0);
}
}
#endif /* PIOS_INCLUDE_COM */
#endif

View File

@ -55,7 +55,6 @@ static const struct pios_spi_cfg
.ahb_clk = RCC_AHBPeriph_DMA1,
.irq = {
.handler = NULL,
.flags = (DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 | DMA1_FLAG_GL4),
.init = {
.NVIC_IRQChannel = DMA1_Channel4_IRQn,
@ -133,11 +132,18 @@ void PIOS_SPI_op_irq_handler(void) {
#include "bl_fsm.h" /* lfsm_* */
static bool board_init_complete = false;
void PIOS_Board_Init() {
if (board_init_complete) {
return;
}
/* Set up the SPI interface to the OP board */
if (PIOS_SPI_Init(&pios_spi_op_id, &pios_spi_op_cfg)) {
PIOS_DEBUG_Assert(0);
}
lfsm_attach(pios_spi_op_id);
lfsm_init();
board_init_complete = true;
}

View File

@ -94,8 +94,6 @@ DOXYGENDIR = ../Doc/Doxygen
SRC += $(OPSYSTEM)/main.c
SRC += $(OPSYSTEM)/pios_board.c
SRC += $(OPSYSTEM)/op_dfu.c
SRC += $(FLIGHTLIB)/stopwatch.c
## PIOS Hardware (STM32F10x)
SRC += $(PIOSSTM32F10X)/pios_sys.c
@ -139,7 +137,6 @@ SRC += $(STMSPDSRCDIR)/stm32f10x_pwr.c
SRC += $(STMSPDSRCDIR)/stm32f10x_rcc.c
SRC += $(STMSPDSRCDIR)/stm32f10x_rtc.c
SRC += $(STMSPDSRCDIR)/stm32f10x_spi.c
SRC += $(STMSPDSRCDIR)/stm32f10x_tim.c
SRC += $(STMSPDSRCDIR)/stm32f10x_usart.c
SRC += $(STMSPDSRCDIR)/stm32f10x_dbgmcu.c
SRC += $(STMSPDSRCDIR)/misc.c

View File

@ -28,7 +28,6 @@
/* Bootloader Includes */
#include <pios.h>
#include <pios_board_info.h>
#include "stopwatch.h"
#include "op_dfu.h"
#include "usb_lib.h"
#include "pios_iap.h"
@ -47,9 +46,9 @@ pFunction Jump_To_Application;
uint32_t JumpAddress;
/// LEDs PWM
uint32_t period1 = 50; // *100 uS -> 5 mS
uint32_t period1 = 5000; // 5 mS
uint32_t sweep_steps1 = 100; // * 5 mS -> 500 mS
uint32_t period2 = 50; // *100 uS -> 5 mS
uint32_t period2 = 5000; // 5 mS
uint32_t sweep_steps2 = 100; // * 5 mS -> 500 mS
@ -70,7 +69,6 @@ uint8_t processRX();
void jump_to_app();
#define BLUE LED1
#define LED_PWM_TIMER TIM1
int main() {
PIOS_SYS_Init();
if (BSL_HOLD_STATE == 0)
@ -93,13 +91,17 @@ int main() {
DeviceState = DFUidle;
else
DeviceState = BLidle;
STOPWATCH_Init(100, LED_PWM_TIMER);
} else
JumpToApp = TRUE;
STOPWATCH_Reset(LED_PWM_TIMER);
uint32_t stopwatch = 0;
uint32_t prev_ticks = PIOS_DELAY_GetuS();
while (TRUE) {
/* Update the stopwatch */
uint32_t elapsed_ticks = PIOS_DELAY_GetuSSince(prev_ticks);
prev_ticks += elapsed_ticks;
stopwatch += elapsed_ticks;
if (JumpToApp == TRUE)
jump_to_app();
@ -107,19 +109,19 @@ int main() {
case Last_operation_Success:
case uploadingStarting:
case DFUidle:
period1 = 50;
period1 = 5000;
sweep_steps1 = 100;
PIOS_LED_Off(BLUE);
period2 = 0;
break;
case uploading:
period1 = 50;
period1 = 5000;
sweep_steps1 = 100;
period2 = 25;
period2 = 2500;
sweep_steps2 = 50;
break;
case downloading:
period1 = 25;
period1 = 2500;
sweep_steps1 = 50;
PIOS_LED_Off(BLUE);
period2 = 0;
@ -130,14 +132,14 @@ int main() {
period2 = 0;
break;
default://error
period1 = 50;
period1 = 5000;
sweep_steps1 = 100;
period2 = 50;
period2 = 5000;
sweep_steps2 = 100;
}
if (period1 != 0) {
if (LedPWM(period1, sweep_steps1, STOPWATCH_ValueGet(LED_PWM_TIMER)))
if (LedPWM(period1, sweep_steps1, stopwatch))
PIOS_LED_On(BLUE);
else
PIOS_LED_Off(BLUE);
@ -145,16 +147,16 @@ int main() {
PIOS_LED_On(BLUE);
if (period2 != 0) {
if (LedPWM(period2, sweep_steps2, STOPWATCH_ValueGet(LED_PWM_TIMER)))
if (LedPWM(period2, sweep_steps2, stopwatch))
PIOS_LED_On(BLUE);
else
PIOS_LED_Off(BLUE);
} else
PIOS_LED_Off(BLUE);
if (STOPWATCH_ValueGet(LED_PWM_TIMER) > 100 * 50 * 100)
STOPWATCH_Reset(LED_PWM_TIMER);
if ((STOPWATCH_ValueGet(LED_PWM_TIMER) > 60000) && (DeviceState
if (stopwatch > 50 * 1000 * 1000)
stopwatch = 0;
if ((stopwatch > 6 * 1000 * 1000) && (DeviceState
== BLidle))
JumpToApp = TRUE;
@ -185,20 +187,21 @@ void jump_to_app() {
}
}
uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count) {
uint32_t pwm_duty = ((count / pwm_period) % pwm_sweep_steps)
/ (pwm_sweep_steps / pwm_period);
if ((count % (2 * pwm_period * pwm_sweep_steps)) > pwm_period
* pwm_sweep_steps)
pwm_duty = pwm_period - pwm_duty; // negative direction each 50*100 ticks
uint32_t curr_step = (count / pwm_period) % pwm_sweep_steps; /* 0 - pwm_sweep_steps */
uint32_t pwm_duty = pwm_period * curr_step / pwm_sweep_steps; /* fraction of pwm_period */
uint32_t curr_sweep = (count / (pwm_period * pwm_sweep_steps)); /* ticks once per full sweep */
if (curr_sweep & 1) {
pwm_duty = pwm_period - pwm_duty; /* reverse direction in odd sweeps */
}
return ((count % pwm_period) > pwm_duty) ? 1 : 0;
}
uint8_t processRX() {
while (PIOS_COM_ReceiveBufferUsed(PIOS_COM_TELEM_USB) >= 63) {
for (int32_t x = 0; x < 63; ++x) {
mReceive_Buffer[x] = PIOS_COM_ReceiveBuffer(PIOS_COM_TELEM_USB);
if (PIOS_COM_ReceiveBuffer(PIOS_COM_TELEM_USB, mReceive_Buffer, 63, 0) == 63) {
processComand(mReceive_Buffer);
}
processComand(mReceive_Buffer);
}
return TRUE;
}

View File

@ -31,10 +31,31 @@
#include <pios_com_priv.h>
#define PIOS_COM_TELEM_USB_RX_BUF_LEN 192
#define PIOS_COM_TELEM_USB_TX_BUF_LEN 192
static uint8_t pios_com_telem_usb_rx_buffer[PIOS_COM_TELEM_USB_RX_BUF_LEN];
static uint8_t pios_com_telem_usb_tx_buffer[PIOS_COM_TELEM_USB_TX_BUF_LEN];
#endif /* PIOS_INCLUDE_COM */
// ***********************************************************************************
#if defined(PIOS_INCLUDE_USB_HID)
#include "pios_usb_hid_priv.h"
static const struct pios_usb_hid_cfg pios_usb_hid_main_cfg = {
.irq = {
.init = {
.NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
};
#endif /* PIOS_INCLUDE_USB_HID */
extern const struct pios_com_driver pios_usb_com_driver;
uint32_t pios_com_telem_usb_id;
@ -44,7 +65,12 @@ uint32_t pios_com_telem_usb_id;
* initializes all the core subsystems on this specific hardware
* called from System/openpilot.c
*/
static bool board_init_complete = false;
void PIOS_Board_Init(void) {
if (board_init_complete) {
return;
}
/* Enable Prefetch Buffer */
FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
@ -58,13 +84,20 @@ void PIOS_Board_Init(void) {
PIOS_GPIO_Init();
#if defined(PIOS_INCLUDE_USB_HID)
PIOS_USB_HID_Init(0);
uint32_t pios_usb_hid_id;
if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_main_cfg)) {
PIOS_Assert(0);
}
#if defined(PIOS_INCLUDE_COM)
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_com_driver, 0)) {
PIOS_DEBUG_Assert(0);
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_com_driver, pios_usb_hid_id,
pios_com_telem_usb_rx_buffer, sizeof(pios_com_telem_usb_rx_buffer),
pios_com_telem_usb_tx_buffer, sizeof(pios_com_telem_usb_tx_buffer))) {
PIOS_Assert(0);
}
#endif /* PIOS_INCLUDE_COM */
#endif /* PIOS_INCLUDE_USB_HID */
#endif /* PIOS_INCLUDE_USB_HID */
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_CRC, ENABLE);//TODO Tirar
board_init_complete = true;
}

View File

@ -250,10 +250,9 @@ uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count) {
uint8_t processRX() {
if (ProgPort == Usb) {
while (PIOS_COM_ReceiveBufferUsed(PIOS_COM_TELEM_USB) >= 63) {
for (int32_t x = 0; x < 63; ++x) {
mReceive_Buffer[x] = PIOS_COM_ReceiveBuffer(PIOS_COM_TELEM_USB);
if (PIOS_COM_ReceiveBuffer(PIOS_COM_TELEM_USB, mReceive_Buffer, 63, 0) == 63) {
processComand(mReceive_Buffer);
}
processComand(mReceive_Buffer);
}
} else if (ProgPort == Serial) {
@ -279,7 +278,12 @@ void SSP_CallBack(uint8_t *buf, uint16_t len) {
}
int16_t SSP_SerialRead(void) {
if (PIOS_COM_ReceiveBufferUsed(PIOS_COM_TELEM_RF) > 0) {
return PIOS_COM_ReceiveBuffer(PIOS_COM_TELEM_RF);
uint8_t byte;
if (PIOS_COM_ReceiveBuffer(PIOS_COM_TELEM_RF, &byte, 1, 0) == 1) {
return byte;
} else {
return -1;
}
} else
return -1;
}

View File

@ -60,7 +60,6 @@ const struct pios_spi_cfg
.ahb_clk = RCC_AHBPeriph_DMA1,
.irq = {
.handler = NULL,
.flags = (DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 | DMA1_FLAG_GL4),
.init = {
.NVIC_IRQChannel = DMA1_Channel4_IRQn,
@ -157,7 +156,6 @@ const struct pios_usart_cfg pios_usart_telem_cfg = {
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
}, .irq = {
.handler = NULL,
.init = {
.NVIC_IRQChannel = USART2_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
@ -186,8 +184,35 @@ const struct pios_usart_cfg pios_usart_telem_cfg = {
#include "pios_com_priv.h"
#define PIOS_COM_TELEM_USB_RX_BUF_LEN 192
#define PIOS_COM_TELEM_USB_TX_BUF_LEN 192
static uint8_t pios_com_telem_usb_rx_buffer[PIOS_COM_TELEM_USB_RX_BUF_LEN];
static uint8_t pios_com_telem_usb_tx_buffer[PIOS_COM_TELEM_USB_TX_BUF_LEN];
#define PIOS_COM_TELEM_RF_RX_BUF_LEN 192
#define PIOS_COM_TELEM_RF_TX_BUF_LEN 192
static uint8_t pios_com_telem_rf_rx_buffer[PIOS_COM_TELEM_RF_RX_BUF_LEN];
static uint8_t pios_com_telem_rf_tx_buffer[PIOS_COM_TELEM_RF_TX_BUF_LEN];
#endif /* PIOS_INCLUDE_COM */
#if defined(PIOS_INCLUDE_USB_HID)
#include "pios_usb_hid_priv.h"
static const struct pios_usb_hid_cfg pios_usb_hid_main_cfg = {
.irq = {
.init = {
.NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
};
#endif /* PIOS_INCLUDE_USB_HID */
extern const struct pios_com_driver pios_usb_com_driver;
uint32_t pios_com_telem_rf_id;
@ -200,7 +225,11 @@ uint32_t pios_com_telem_usb_id;
* initializes all the core subsystems on this specific hardware
* called from System/openpilot.c
*/
static bool board_init_complete = false;
void PIOS_Board_Init(void) {
if (board_init_complete) {
return;
}
/* Enable Prefetch Buffer */
FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
@ -218,7 +247,9 @@ void PIOS_Board_Init(void) {
PIOS_DEBUG_Assert(0);
}
if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_usart_com_driver,
pios_usart_telem_rf_id)) {
pios_usart_telem_rf_id,
pios_com_telem_rf_rx_buffer, sizeof(pios_com_telem_rf_rx_buffer),
pios_com_telem_rf_tx_buffer, sizeof(pios_com_telem_rf_tx_buffer))) {
PIOS_DEBUG_Assert(0);
}
#endif /* PIOS_INCLUDE_COM */
@ -226,13 +257,16 @@ void PIOS_Board_Init(void) {
PIOS_GPIO_Init();
#if defined(PIOS_INCLUDE_USB_HID)
PIOS_USB_HID_Init(0);
uint32_t pios_usb_hid_id;
PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_main_cfg);
#if defined(PIOS_INCLUDE_COM)
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_com_driver, 0)) {
PIOS_DEBUG_Assert(0);
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_com_driver, pios_usb_hid_id,
pios_com_telem_usb_rx_buffer, sizeof(pios_com_telem_usb_rx_buffer),
pios_com_telem_usb_tx_buffer, sizeof(pios_com_telem_usb_tx_buffer))) {
PIOS_Assert(0);
}
#endif /* PIOS_INCLUDE_COM */
#endif /* PIOS_INCLUDE_USB_HID */
#endif /* PIOS_INCLUDE_USB_HID */
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_CRC, ENABLE);//TODO Tirar
@ -243,6 +277,8 @@ void PIOS_Board_Init(void) {
/* Bind the AHRS comms layer to the AHRS SPI link */
PIOS_OPAHRS_Attach(pios_spi_ahrs_id);
board_init_complete = true;
}
/**

View File

@ -94,8 +94,6 @@ DOXYGENDIR = ../Doc/Doxygen
SRC += $(OPSYSTEM)/main.c
SRC += $(OPSYSTEM)/pios_board.c
SRC += $(OPSYSTEM)/op_dfu.c
SRC += $(FLIGHTLIB)/stopwatch.c
## PIOS Hardware (STM32F10x)
SRC += $(PIOSSTM32F10X)/pios_sys.c
@ -138,7 +136,6 @@ SRC += $(STMSPDSRCDIR)/stm32f10x_pwr.c
SRC += $(STMSPDSRCDIR)/stm32f10x_rcc.c
SRC += $(STMSPDSRCDIR)/stm32f10x_rtc.c
SRC += $(STMSPDSRCDIR)/stm32f10x_spi.c
SRC += $(STMSPDSRCDIR)/stm32f10x_tim.c
SRC += $(STMSPDSRCDIR)/stm32f10x_usart.c
SRC += $(STMSPDSRCDIR)/stm32f10x_dbgmcu.c
SRC += $(STMSPDSRCDIR)/misc.c

View File

@ -28,7 +28,6 @@
/* Bootloader Includes */
#include <pios.h>
#include <pios_board_info.h>
#include "stopwatch.h"
#include "op_dfu.h"
#include "usb_lib.h"
#include "pios_iap.h"
@ -47,9 +46,9 @@ pFunction Jump_To_Application;
uint32_t JumpAddress;
/// LEDs PWM
uint32_t period1 = 50; // *100 uS -> 5 mS
uint32_t period1 = 5000; // 5 mS
uint32_t sweep_steps1 = 100; // * 5 mS -> 500 mS
uint32_t period2 = 50; // *100 uS -> 5 mS
uint32_t period2 = 5000; // 5 mS
uint32_t sweep_steps2 = 100; // * 5 mS -> 500 mS
@ -71,7 +70,6 @@ void jump_to_app();
#define BLUE LED1
#define RED LED4
#define LED_PWM_TIMER TIM3
int main() {
/* NOTE: Do NOT modify the following start-up sequence */
/* Any new initialization functions should be added in OpenPilotInit() */
@ -98,35 +96,37 @@ int main() {
DeviceState = DFUidle;
else
DeviceState = BLidle;
STOPWATCH_Init(100, LED_PWM_TIMER);
} else
JumpToApp = TRUE;
STOPWATCH_Reset(LED_PWM_TIMER);
uint32_t stopwatch = 0;
uint32_t prev_ticks = PIOS_DELAY_GetuS();
while (TRUE) {
/* Update the stopwatch */
uint32_t elapsed_ticks = PIOS_DELAY_GetuSSince(prev_ticks);
prev_ticks += elapsed_ticks;
stopwatch += elapsed_ticks;
if (JumpToApp == TRUE)
jump_to_app();
//pwm_period = 50; // *100 uS -> 5 mS
//pwm_sweep_steps =100; // * 5 mS -> 500 mS
switch (DeviceState) {
case Last_operation_Success:
case uploadingStarting:
case DFUidle:
period1 = 50;
period1 = 5000;
sweep_steps1 = 100;
PIOS_LED_Off(RED);
period2 = 0;
break;
case uploading:
period1 = 50;
period1 = 5000;
sweep_steps1 = 100;
period2 = 25;
period2 = 2500;
sweep_steps2 = 50;
break;
case downloading:
period1 = 25;
period1 = 2500;
sweep_steps1 = 50;
PIOS_LED_Off(RED);
period2 = 0;
@ -137,14 +137,14 @@ int main() {
period2 = 0;
break;
default://error
period1 = 50;
period1 = 5000;
sweep_steps1 = 100;
period2 = 50;
period2 = 5000;
sweep_steps2 = 100;
}
if (period1 != 0) {
if (LedPWM(period1, sweep_steps1, STOPWATCH_ValueGet(LED_PWM_TIMER)))
if (LedPWM(period1, sweep_steps1, stopwatch))
PIOS_LED_On(BLUE);
else
PIOS_LED_Off(BLUE);
@ -152,16 +152,16 @@ int main() {
PIOS_LED_On(BLUE);
if (period2 != 0) {
if (LedPWM(period2, sweep_steps2, STOPWATCH_ValueGet(LED_PWM_TIMER)))
if (LedPWM(period2, sweep_steps2, stopwatch))
PIOS_LED_On(RED);
else
PIOS_LED_Off(RED);
} else
PIOS_LED_Off(RED);
if (STOPWATCH_ValueGet(LED_PWM_TIMER) > 100 * 50 * 100)
STOPWATCH_Reset(LED_PWM_TIMER);
if ((STOPWATCH_ValueGet(LED_PWM_TIMER) > 60000) && (DeviceState
if (stopwatch > 50 * 1000 * 1000)
stopwatch = 0;
if ((stopwatch > 6 * 1000 * 1000) && (DeviceState
== BLidle))
JumpToApp = TRUE;
@ -193,20 +193,21 @@ void jump_to_app() {
}
}
uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count) {
uint32_t pwm_duty = ((count / pwm_period) % pwm_sweep_steps)
/ (pwm_sweep_steps / pwm_period);
if ((count % (2 * pwm_period * pwm_sweep_steps)) > pwm_period
* pwm_sweep_steps)
pwm_duty = pwm_period - pwm_duty; // negative direction each 50*100 ticks
uint32_t curr_step = (count / pwm_period) % pwm_sweep_steps; /* 0 - pwm_sweep_steps */
uint32_t pwm_duty = pwm_period * curr_step / pwm_sweep_steps; /* fraction of pwm_period */
uint32_t curr_sweep = (count / (pwm_period * pwm_sweep_steps)); /* ticks once per full sweep */
if (curr_sweep & 1) {
pwm_duty = pwm_period - pwm_duty; /* reverse direction in odd sweeps */
}
return ((count % pwm_period) > pwm_duty) ? 1 : 0;
}
uint8_t processRX() {
while (PIOS_COM_ReceiveBufferUsed(PIOS_COM_TELEM_USB) >= 63) {
for (int32_t x = 0; x < 63; ++x) {
mReceive_Buffer[x] = PIOS_COM_ReceiveBuffer(PIOS_COM_TELEM_USB);
if (PIOS_COM_ReceiveBuffer(PIOS_COM_TELEM_USB, mReceive_Buffer, 63, 0) == 63) {
processComand(mReceive_Buffer);
}
processComand(mReceive_Buffer);
}
return TRUE;
}

View File

@ -31,10 +31,31 @@
#include <pios_com_priv.h>
#define PIOS_COM_TELEM_USB_RX_BUF_LEN 192
#define PIOS_COM_TELEM_USB_TX_BUF_LEN 192
static uint8_t pios_com_telem_usb_rx_buffer[PIOS_COM_TELEM_USB_RX_BUF_LEN];
static uint8_t pios_com_telem_usb_tx_buffer[PIOS_COM_TELEM_USB_TX_BUF_LEN];
#endif /* PIOS_INCLUDE_COM */
// ***********************************************************************************
#if defined(PIOS_INCLUDE_USB_HID)
#include "pios_usb_hid_priv.h"
static const struct pios_usb_hid_cfg pios_usb_hid_main_cfg = {
.irq = {
.init = {
.NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
};
#endif /* PIOS_INCLUDE_USB_HID */
extern const struct pios_com_driver pios_usb_com_driver;
uint32_t pios_com_telem_usb_id;
@ -44,7 +65,12 @@ uint32_t pios_com_telem_usb_id;
* initializes all the core subsystems on this specific hardware
* called from System/openpilot.c
*/
static bool board_init_complete = false;
void PIOS_Board_Init(void) {
if (board_init_complete) {
return;
}
/* Enable Prefetch Buffer */
FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
@ -58,13 +84,18 @@ void PIOS_Board_Init(void) {
PIOS_GPIO_Init();
#if defined(PIOS_INCLUDE_USB_HID)
PIOS_USB_HID_Init(0);
uint32_t pios_usb_hid_id;
PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_main_cfg);
#if defined(PIOS_INCLUDE_COM)
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_com_driver, 0)) {
PIOS_DEBUG_Assert(0);
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_com_driver, pios_usb_hid_id,
pios_com_telem_usb_rx_buffer, sizeof(pios_com_telem_usb_rx_buffer),
pios_com_telem_usb_tx_buffer, sizeof(pios_com_telem_usb_tx_buffer))) {
PIOS_Assert(0);
}
#endif /* PIOS_INCLUDE_COM */
#endif /* PIOS_INCLUDE_USB_HID */
#endif /* PIOS_INCLUDE_USB_HID */
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_CRC, ENABLE);//TODO Tirar
board_init_complete = true;
}

View File

@ -63,7 +63,6 @@ static const struct pios_spi_cfg pios_spi_flash_accel_cfg = {
.ahb_clk = RCC_AHBPeriph_DMA1,
.irq = {
.handler = NULL,
.flags = (DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 | DMA1_FLAG_GL4),
.init = {
.NVIC_IRQChannel = DMA1_Channel4_IRQn,
@ -156,7 +155,6 @@ static const struct pios_adc_cfg pios_adc_cfg = {
.dma = {
.ahb_clk = RCC_AHBPeriph_DMA1,
.irq = {
.handler = NULL,
.flags = (DMA1_FLAG_TC1 | DMA1_FLAG_TE1 | DMA1_FLAG_HT1 | DMA1_FLAG_GL1),
.init = {
.NVIC_IRQChannel = DMA1_Channel1_IRQn,
@ -216,7 +214,6 @@ static const struct pios_usart_cfg pios_usart_telem_main_cfg = {
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
},
.irq = {
.handler = NULL,
.init = {
.NVIC_IRQChannel = USART1_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
@ -253,7 +250,6 @@ static const struct pios_usart_cfg pios_usart_telem_flexi_cfg = {
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
},
.irq = {
.handler = NULL,
.init = {
.NVIC_IRQChannel = USART3_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
@ -295,7 +291,6 @@ static const struct pios_usart_cfg pios_usart_gps_main_cfg = {
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
},
.irq = {
.handler = NULL,
.init = {
.NVIC_IRQChannel = USART1_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
@ -332,7 +327,6 @@ static const struct pios_usart_cfg pios_usart_gps_flexi_cfg = {
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
},
.irq = {
.handler = NULL,
.init = {
.NVIC_IRQChannel = USART3_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
@ -376,7 +370,6 @@ static const struct pios_usart_cfg pios_usart_spektrum_main_cfg = {
.USART_Mode = USART_Mode_Rx,
},
.irq = {
.handler = PIOS_SPEKTRUM_irq_handler,
.init = {
.NVIC_IRQChannel = USART1_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
@ -425,7 +418,6 @@ static const struct pios_usart_cfg pios_usart_spektrum_flexi_cfg = {
.USART_Mode = USART_Mode_Rx,
},
.irq = {
.handler = PIOS_SPEKTRUM_irq_handler,
.init = {
.NVIC_IRQChannel = USART3_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
@ -482,7 +474,6 @@ static const struct pios_usart_cfg pios_usart_sbus_main_cfg = {
.USART_Mode = USART_Mode_Rx,
},
.irq = {
.handler = PIOS_SBUS_irq_handler,
.init = {
.NVIC_IRQChannel = USART1_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
@ -531,6 +522,14 @@ static const struct pios_sbus_cfg pios_sbus_cfg = {
#include "pios_com_priv.h"
#define PIOS_COM_TELEM_RF_RX_BUF_LEN 192
#define PIOS_COM_TELEM_RF_TX_BUF_LEN 192
#define PIOS_COM_GPS_RX_BUF_LEN 96
#define PIOS_COM_TELEM_USB_RX_BUF_LEN 192
#define PIOS_COM_TELEM_USB_TX_BUF_LEN 192
#endif /* PIOS_INCLUDE_COM */
#if defined(PIOS_INCLUDE_RTC)
@ -545,7 +544,6 @@ static const struct pios_rtc_cfg pios_rtc_main_cfg = {
.clksrc = RCC_RTCCLKSource_HSE_Div128,
.prescaler = 100,
.irq = {
.handler = NULL,
.init = {
.NVIC_IRQChannel = RTC_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
@ -666,7 +664,6 @@ const struct pios_ppm_cfg pios_ppm_cfg = {
},
.remap = 0,
.irq = {
.handler = TIM4_IRQHandler,
.init = {
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
@ -761,7 +758,6 @@ const struct pios_pwm_cfg pios_pwm_cfg = {
},
.remap = 0,
.irq = {
.handler = NULL,
.init = {
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
@ -826,7 +822,6 @@ static const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = {
},
},
.event = {
.handler = NULL,
.flags = 0, /* FIXME: check this */
.init = {
.NVIC_IRQChannel = I2C2_EV_IRQn,
@ -836,7 +831,6 @@ static const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = {
},
},
.error = {
.handler = NULL,
.flags = 0, /* FIXME: check this */
.init = {
.NVIC_IRQChannel = I2C2_ER_IRQn,
@ -869,6 +863,21 @@ struct pios_rcvr_channel_map pios_rcvr_channel_to_id_map[PIOS_RCVR_MAX_CHANNELS]
uint32_t pios_rcvr_max_channel;
#endif /* PIOS_INCLUDE_RCVR */
#if defined(PIOS_INCLUDE_USB_HID)
#include "pios_usb_hid_priv.h"
static const struct pios_usb_hid_cfg pios_usb_hid_main_cfg = {
.irq = {
.init = {
.NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
};
#endif /* PIOS_INCLUDE_USB_HID */
extern const struct pios_com_driver pios_usb_com_driver;
uint32_t pios_com_telem_rf_id;
@ -925,7 +934,14 @@ void PIOS_Board_Init(void) {
if (PIOS_USART_Init(&pios_usart_telem_rf_id, &pios_usart_telem_main_cfg)) {
PIOS_Assert(0);
}
if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_usart_com_driver, pios_usart_telem_rf_id)) {
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);
}
}
@ -934,12 +950,15 @@ void PIOS_Board_Init(void) {
case HWSETTINGS_CC_MAINPORT_SBUS:
#if defined(PIOS_INCLUDE_SBUS)
{
PIOS_SBUS_Init(&pios_sbus_cfg);
uint32_t pios_usart_sbus_id;
if (PIOS_USART_Init(&pios_usart_sbus_id, &pios_usart_sbus_main_cfg)) {
PIOS_Assert(0);
}
uint32_t pios_sbus_id;
if (PIOS_SBUS_Init(&pios_sbus_id, &pios_sbus_cfg, &pios_usart_com_driver, pios_usart_sbus_id)) {
PIOS_Assert(0);
}
}
#endif /* PIOS_INCLUDE_SBUS */
break;
@ -950,7 +969,12 @@ void PIOS_Board_Init(void) {
if (PIOS_USART_Init(&pios_usart_gps_id, &pios_usart_gps_main_cfg)) {
PIOS_Assert(0);
}
if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_gps_id)) {
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);
}
}
@ -959,13 +983,15 @@ void PIOS_Board_Init(void) {
case HWSETTINGS_CC_MAINPORT_SPEKTRUM:
#if defined(PIOS_INCLUDE_SPEKTRUM)
{
/* SPEKTRUM init must come before usart init since it may use Rx pin for bind */
PIOS_SPEKTRUM_Init(&pios_spektrum_main_cfg, false);
uint32_t pios_usart_spektrum_id;
if (PIOS_USART_Init(&pios_usart_spektrum_id, &pios_usart_spektrum_main_cfg)) {
PIOS_Assert(0);
}
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)) {
PIOS_Assert(0);
}
}
#endif /* PIOS_INCLUDE_SPEKTRUM */
break;
@ -987,7 +1013,13 @@ void PIOS_Board_Init(void) {
if (PIOS_USART_Init(&pios_usart_telem_rf_id, &pios_usart_telem_flexi_cfg)) {
PIOS_Assert(0);
}
if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_usart_com_driver, pios_usart_telem_rf_id)) {
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);
}
}
@ -1000,7 +1032,11 @@ void PIOS_Board_Init(void) {
if (PIOS_USART_Init(&pios_usart_gps_id, &pios_usart_gps_flexi_cfg)) {
PIOS_Assert(0);
}
if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_gps_id)) {
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);
}
}
@ -1009,13 +1045,15 @@ void PIOS_Board_Init(void) {
case HWSETTINGS_CC_FLEXIPORT_SPEKTRUM:
#if defined(PIOS_INCLUDE_SPEKTRUM)
{
/* SPEKTRUM init must come before usart init since it may use Rx pin for bind */
PIOS_SPEKTRUM_Init(&pios_spektrum_flexi_cfg, false);
uint32_t pios_usart_spektrum_id;
if (PIOS_USART_Init(&pios_usart_spektrum_id, &pios_usart_spektrum_flexi_cfg)) {
PIOS_Assert(0);
}
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)) {
PIOS_Assert(0);
}
}
#endif /* PIOS_INCLUDE_SPEKTRUM */
break;
@ -1042,7 +1080,7 @@ void PIOS_Board_Init(void) {
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);
PIOS_Assert(0);
}
for (uint8_t i = 0;
i < PIOS_PWM_NUM_INPUTS && pios_rcvr_max_channel < NELEMENTS(pios_rcvr_channel_to_id_map);
@ -1058,7 +1096,7 @@ void PIOS_Board_Init(void) {
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);
PIOS_Assert(0);
}
for (uint8_t i = 0;
i < PIOS_PPM_NUM_INPUTS && pios_rcvr_max_channel < NELEMENTS(pios_rcvr_channel_to_id_map);
@ -1114,9 +1152,16 @@ void PIOS_Board_Init(void) {
PIOS_GPIO_Init();
#if defined(PIOS_INCLUDE_USB_HID)
PIOS_USB_HID_Init(0);
uint32_t pios_usb_hid_id;
PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_main_cfg);
#if defined(PIOS_INCLUDE_COM)
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_com_driver, 0)) {
uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_RX_BUF_LEN);
uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_TX_BUF_LEN);
PIOS_Assert(rx_buffer);
PIOS_Assert(tx_buffer);
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_com_driver, pios_usb_hid_id,
rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN,
tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) {
PIOS_Assert(0);
}
#endif /* PIOS_INCLUDE_COM */

View File

@ -61,7 +61,6 @@ static const struct pios_spi_cfg pios_spi_op_mag_cfg = {
.ahb_clk = RCC_AHBPeriph_DMA1,
.irq = {
.handler = NULL,
.flags =
(DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 |
DMA1_FLAG_GL4),
@ -175,7 +174,6 @@ static const struct pios_spi_cfg pios_spi_accel_cfg = {
.ahb_clk = RCC_AHBPeriph_DMA1,
.irq = {
.handler = NULL,
.flags = (DMA1_FLAG_TC2 | DMA1_FLAG_TE2 | DMA1_FLAG_HT2 | DMA1_FLAG_GL2),
.init = {
.NVIC_IRQChannel = DMA1_Channel2_IRQn,
@ -277,7 +275,6 @@ static const struct pios_usart_cfg pios_usart_gps_cfg = {
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
},
.irq = {
.handler = NULL,
.init = {
.NVIC_IRQChannel = USART1_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
@ -321,7 +318,6 @@ static const struct pios_usart_cfg pios_usart_aux_cfg = {
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
},
.irq = {
.handler = NULL,
.init = {
.NVIC_IRQChannel = USART4_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
@ -350,6 +346,21 @@ static const struct pios_usart_cfg pios_usart_aux_cfg = {
#endif /* PIOS_COM_AUX */
#if defined(PIOS_INCLUDE_COM)
#include <pios_com_priv.h>
#if 0
#define PIOS_COM_AUX_TX_BUF_LEN 192
static uint8_t pios_com_aux_tx_buffer[PIOS_COM_AUX_TX_BUF_LEN];
#endif
#define PIOS_COM_GPS_RX_BUF_LEN 96
static uint8_t pios_com_gps_rx_buffer[PIOS_COM_GPS_RX_BUF_LEN];
#endif /* PIOS_INCLUDE_COM */
#if defined(PIOS_INCLUDE_I2C)
#include <pios_i2c_priv.h>
@ -393,7 +404,6 @@ static const struct pios_i2c_adapter_cfg pios_i2c_pres_mag_adapter_cfg = {
},
},
.event = {
.handler = NULL,
.flags = 0, /* FIXME: check this */
.init = {
.NVIC_IRQChannel = I2C1_EV_IRQn,
@ -403,7 +413,6 @@ static const struct pios_i2c_adapter_cfg pios_i2c_pres_mag_adapter_cfg = {
},
},
.error = {
.handler = NULL,
.flags = 0, /* FIXME: check this */
.init = {
.NVIC_IRQChannel = I2C1_ER_IRQn,
@ -461,7 +470,6 @@ static const struct pios_i2c_adapter_cfg pios_i2c_gyro_adapter_cfg = {
},
},
.event = {
.handler = NULL,
.flags = 0, /* FIXME: check this */
.init = {
.NVIC_IRQChannel = I2C2_EV_IRQn,
@ -471,7 +479,6 @@ static const struct pios_i2c_adapter_cfg pios_i2c_gyro_adapter_cfg = {
},
},
.error = {
.handler = NULL,
.flags = 0, /* FIXME: check this */
.init = {
.NVIC_IRQChannel = I2C2_ER_IRQn,
@ -525,7 +532,9 @@ void PIOS_Board_Init(void) {
if (PIOS_USART_Init(&pios_usart_gps_id, &pios_usart_gps_cfg)) {
PIOS_DEBUG_Assert(0);
}
if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_gps_id)) {
if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_gps_id,
pios_com_gps_rx_buffer, sizeof(pios_com_gps_rx_buffer),
NULL, 0)) {
PIOS_DEBUG_Assert(0);
}
#endif /* PIOS_INCLUDE_GPS */

View File

@ -329,6 +329,13 @@ static void updateAttitude(AttitudeRawData * attitudeRaw)
q[1] = q[1] + qdot[1];
q[2] = q[2] + qdot[2];
q[3] = q[3] + qdot[3];
if(q[0] < 0) {
q[0] = -q[0];
q[1] = -q[1];
q[2] = -q[2];
q[3] = -q[3];
}
}
// Renomalize

View File

@ -196,8 +196,10 @@ static void gpsTask(void *parameters)
while (PIOS_COM_ReceiveBufferUsed(gpsPort) > 0)
{
int res = GTOP_BIN_update_position(PIOS_COM_ReceiveBuffer(gpsPort), &numChecksumErrors, &numParsingErrors);
if (res >= 0)
uint8_t c;
PIOS_COM_ReceiveBuffer(gpsPort, &c, 1, 0);
if (GTOP_BIN_update_position(c, &numChecksumErrors, &numParsingErrors) >= 0)
{
numUpdates++;
@ -213,7 +215,8 @@ static void gpsTask(void *parameters)
// This blocks the task until there is something on the buffer
while (PIOS_COM_ReceiveBufferUsed(gpsPort) > 0)
{
char c = PIOS_COM_ReceiveBuffer(gpsPort);
uint8_t c;
PIOS_COM_ReceiveBuffer(gpsPort, &c, 1, 0);
// detect start while acquiring stream
if (!start_flag && (c == '$'))

View File

@ -84,6 +84,7 @@ uint8_t max_axis_lock = 0;
uint8_t max_axislock_rate = 0;
float weak_leveling_kp = 0;
uint8_t weak_leveling_max = 0;
bool lowThrottleZeroIntegral;
pid_type pids[PID_MAX];
@ -329,6 +330,7 @@ static void stabilizationTask(void* parameters)
}
if(flightStatus.Armed != FLIGHTSTATUS_ARMED_ARMED ||
(lowThrottleZeroIntegral && stabDesired.Throttle < 0) ||
!shouldUpdate)
{
ZeroPids();
@ -427,6 +429,9 @@ static void SettingsUpdatedCb(UAVObjEvent * ev)
weak_leveling_kp = settings.WeakLevelingKp;
weak_leveling_max = settings.MaxWeakLevelingRate;
// Whether to zero the PID integrals while throttle is low
lowThrottleZeroIntegral = settings.LowThrottleZeroIntegral == STABILIZATIONSETTINGS_LOWTHROTTLEZEROINTEGRAL_TRUE;
// The dT has some jitter iteration to iteration that we don't want to
// make thie result unpredictable. Still, it's nicer to specify the constant
// based on a time (in ms) rather than a fixed multiplier. The error between

View File

@ -305,7 +305,6 @@ static void telemetryTxPriTask(void *parameters)
static void telemetryRxTask(void *parameters)
{
uint32_t inputPort;
int32_t len;
// Task loop
while (1) {
@ -319,14 +318,20 @@ static void telemetryRxTask(void *parameters)
inputPort = telemetryPort;
}
// Block until data are available
// TODO: Currently we periodically check the buffer for data, update once the PIOS_COM is made blocking
len = PIOS_COM_ReceiveBufferUsed(inputPort);
for (int32_t n = 0; n < len; ++n) {
UAVTalkProcessInputStream(PIOS_COM_ReceiveBuffer(inputPort));
}
vTaskDelay(5); // <- remove when blocking calls are implemented
if (inputPort) {
// Block until data are available
uint8_t serial_data[1];
uint16_t bytes_to_process;
bytes_to_process = PIOS_COM_ReceiveBuffer(inputPort, serial_data, sizeof(serial_data), 500);
if (bytes_to_process > 0) {
for (uint8_t i = 0; i < bytes_to_process; i++) {
UAVTalkProcessInputStream(serial_data[i]);
}
}
} else {
vTaskDelay(5);
}
}
}
@ -350,7 +355,11 @@ static int32_t transmitData(uint8_t * data, int32_t length)
outputPort = telemetryPort;
}
return PIOS_COM_SendBufferNonBlocking(outputPort, data, length);
if (outputPort) {
return PIOS_COM_SendBufferNonBlocking(outputPort, data, length);
} else {
return -1;
}
}
/**
@ -506,20 +515,16 @@ static void updateSettings()
// Retrieve settings
TelemetrySettingsGet(&settings);
// Set port speed
if (settings.Speed == TELEMETRYSETTINGS_SPEED_2400) PIOS_COM_ChangeBaud(telemetryPort, 2400);
else
if (settings.Speed == TELEMETRYSETTINGS_SPEED_4800) PIOS_COM_ChangeBaud(telemetryPort, 4800);
else
if (settings.Speed == TELEMETRYSETTINGS_SPEED_9600) PIOS_COM_ChangeBaud(telemetryPort, 9600);
else
if (settings.Speed == TELEMETRYSETTINGS_SPEED_19200) PIOS_COM_ChangeBaud(telemetryPort, 19200);
else
if (settings.Speed == TELEMETRYSETTINGS_SPEED_38400) PIOS_COM_ChangeBaud(telemetryPort, 38400);
else
if (settings.Speed == TELEMETRYSETTINGS_SPEED_57600) PIOS_COM_ChangeBaud(telemetryPort, 57600);
else
if (settings.Speed == TELEMETRYSETTINGS_SPEED_115200) PIOS_COM_ChangeBaud(telemetryPort, 115200);
if (telemetryPort) {
// Set port speed
if (settings.Speed == TELEMETRYSETTINGS_SPEED_2400) PIOS_COM_ChangeBaud(telemetryPort, 2400);
else if (settings.Speed == TELEMETRYSETTINGS_SPEED_4800) PIOS_COM_ChangeBaud(telemetryPort, 4800);
else if (settings.Speed == TELEMETRYSETTINGS_SPEED_9600) PIOS_COM_ChangeBaud(telemetryPort, 9600);
else if (settings.Speed == TELEMETRYSETTINGS_SPEED_19200) PIOS_COM_ChangeBaud(telemetryPort, 19200);
else if (settings.Speed == TELEMETRYSETTINGS_SPEED_38400) PIOS_COM_ChangeBaud(telemetryPort, 38400);
else if (settings.Speed == TELEMETRYSETTINGS_SPEED_57600) PIOS_COM_ChangeBaud(telemetryPort, 57600);
else if (settings.Speed == TELEMETRYSETTINGS_SPEED_115200) PIOS_COM_ChangeBaud(telemetryPort, 115200);
}
}
/**

View File

@ -173,6 +173,8 @@ SRC += $(PIOSPOSIX)/pios_servo.c
SRC += $(PIOSPOSIX)/pios_wdg.c
SRC += $(PIOSPOSIX)/pios_debug.c
SRC += $(PIOSPOSIX)/pios_rcvr.c
## Libraries for flight calculations
#SRC += $(FLIGHTLIB)/fifo_buffer.c
SRC += $(FLIGHTLIB)/WorldMagModel.c

View File

@ -38,7 +38,10 @@
#define PIOS_INCLUDE_COM
#define PIOS_INCLUDE_UDP
#define PIOS_INCLUDE_SERVO
#define PIOS_INCLUDE_RCVR
#define PIOS_RCVR_MAX_CHANNELS 12
#define PIOS_RCVR_MAX_DEVS 3
/* Defaults for Logging */
#define LOG_FILENAME "PIOS.LOG"

View File

@ -64,7 +64,6 @@ static const struct pios_spi_cfg pios_spi_sdcard_cfg = {
.ahb_clk = RCC_AHBPeriph_DMA1,
.irq = {
.handler = NULL,
.flags = (DMA1_FLAG_TC2 | DMA1_FLAG_TE2 | DMA1_FLAG_HT2 | DMA1_FLAG_GL2),
.init = {
.NVIC_IRQChannel = DMA1_Channel2_IRQn,
@ -163,7 +162,6 @@ static const struct pios_spi_cfg pios_spi_ahrs_cfg = {
.ahb_clk = RCC_AHBPeriph_DMA1,
.irq = {
.handler = NULL,
.flags = (DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 | DMA1_FLAG_GL4),
.init = {
.NVIC_IRQChannel = DMA1_Channel4_IRQn,
@ -263,7 +261,6 @@ static const struct pios_adc_cfg pios_adc_cfg = {
.dma = {
.ahb_clk = RCC_AHBPeriph_DMA1,
.irq = {
.handler = NULL,
.flags = (DMA1_FLAG_TC1 | DMA1_FLAG_TE1 | DMA1_FLAG_HT1 | DMA1_FLAG_GL1),
.init = {
.NVIC_IRQChannel = DMA1_Channel1_IRQn,
@ -322,7 +319,6 @@ static const struct pios_usart_cfg pios_usart_telem_cfg = {
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
},
.irq = {
.handler = NULL,
.init = {
.NVIC_IRQChannel = USART2_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
@ -363,7 +359,6 @@ static const struct pios_usart_cfg pios_usart_gps_cfg = {
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
},
.irq = {
.handler = NULL,
.init = {
.NVIC_IRQChannel = USART3_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
@ -404,7 +399,6 @@ static const struct pios_usart_cfg pios_usart_aux_cfg = {
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
},
.irq = {
.handler = NULL,
.init = {
.NVIC_IRQChannel = USART1_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
@ -444,7 +438,6 @@ static const struct pios_rtc_cfg pios_rtc_main_cfg = {
.clksrc = RCC_RTCCLKSource_HSE_Div128,
.prescaler = 100,
.irq = {
.handler = NULL,
.init = {
.NVIC_IRQChannel = RTC_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
@ -461,7 +454,7 @@ void PIOS_RTC_IRQ_Handler (void)
#endif
#ifdef PIOS_COM_SPEKTRUM
#if defined(PIOS_INCLUDE_SPEKTRUM)
/*
* SPEKTRUM USART
*/
@ -478,7 +471,6 @@ static const struct pios_usart_cfg pios_usart_spektrum_cfg = {
.USART_Mode = USART_Mode_Rx,
},
.irq = {
.handler = PIOS_SPEKTRUM_irq_handler,
.init = {
.NVIC_IRQChannel = USART1_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
@ -505,12 +497,6 @@ static const struct pios_usart_cfg pios_usart_spektrum_cfg = {
};
#include <pios_spektrum_priv.h>
static uint32_t pios_usart_spektrum_id;
void PIOS_USART_spektrum_irq_handler(void)
{
PIOS_SPEKTRUM_irq_handler(pios_usart_spektrum_id);
}
static const struct pios_spektrum_cfg pios_spektrum_cfg = {
.bind = {
.gpio = GPIOA,
@ -535,6 +521,14 @@ static const struct pios_spektrum_cfg pios_spektrum_cfg = {
#include "pios_com_priv.h"
#define PIOS_COM_TELEM_RF_RX_BUF_LEN 192
#define PIOS_COM_TELEM_RF_TX_BUF_LEN 192
#define PIOS_COM_GPS_RX_BUF_LEN 96
#define PIOS_COM_TELEM_USB_RX_BUF_LEN 192
#define PIOS_COM_TELEM_USB_TX_BUF_LEN 192
#endif /* PIOS_INCLUDE_COM */
/**
@ -710,7 +704,6 @@ const struct pios_pwm_cfg pios_pwm_cfg = {
},
.remap = GPIO_PartialRemap_TIM3,
.irq = {
.handler = NULL,
.init = {
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
@ -750,7 +743,6 @@ static const struct pios_ppmsv_cfg pios_ppmsv_cfg = {
.TIM_RepetitionCounter = 0x0000,
},
.irq = {
.handler = NULL,
.init = {
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
@ -790,7 +782,6 @@ static const struct pios_ppm_cfg pios_ppm_cfg = {
},
.remap = 0,
.irq = {
.handler = NULL,
.init = {
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
.NVIC_IRQChannelSubPriority = 0,
@ -851,7 +842,6 @@ static const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = {
},
},
.event = {
.handler = NULL,
.flags = 0, /* FIXME: check this */
.init = {
.NVIC_IRQChannel = I2C2_EV_IRQn,
@ -861,7 +851,6 @@ static const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = {
},
},
.error = {
.handler = NULL,
.flags = 0, /* FIXME: check this */
.init = {
.NVIC_IRQChannel = I2C2_ER_IRQn,
@ -979,6 +968,21 @@ struct pios_rcvr_channel_map pios_rcvr_channel_to_id_map[PIOS_RCVR_MAX_CHANNELS]
uint32_t pios_rcvr_max_channel;
#endif /* PIOS_INCLUDE_RCVR */
#if defined(PIOS_INCLUDE_USB_HID)
#include "pios_usb_hid_priv.h"
static const struct pios_usb_hid_cfg pios_usb_hid_main_cfg = {
.irq = {
.init = {
.NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
};
#endif /* PIOS_INCLUDE_USB_HID */
extern const struct pios_com_driver pios_usb_com_driver;
uint32_t pios_com_telem_rf_id;
@ -1046,22 +1050,37 @@ void PIOS_Board_Init(void) {
/* Initialize the PiOS library */
#if defined(PIOS_INCLUDE_COM)
#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);
}
if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_usart_com_driver, pios_usart_telem_rf_id)) {
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);
}
}
#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);
}
if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_gps_id)) {
PIOS_Assert(0);
{
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 */
#endif
@ -1118,23 +1137,28 @@ void PIOS_Board_Init(void) {
#if (PIOS_SPEKTRUM_NUM_INPUTS > PIOS_RCVR_MAX_CHANNELS)
#error More receiver inputs than available devices
#endif
/* SPEKTRUM init must come before comms */
PIOS_SPEKTRUM_Init(&pios_spektrum_cfg, false);
{
uint32_t pios_usart_spektrum_id;
if (PIOS_USART_Init(&pios_usart_spektrum_id, &pios_usart_spektrum_cfg)) {
PIOS_Assert(0);
}
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_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_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++;
}
}
#endif
break;
@ -1145,15 +1169,21 @@ void PIOS_Board_Init(void) {
break;
}
#if defined(PIOS_INCLUDE_USB_HID)
PIOS_USB_HID_Init(0);
uint32_t pios_usb_hid_id;
PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_main_cfg);
#if defined(PIOS_INCLUDE_COM)
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_com_driver, 0)) {
uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_RX_BUF_LEN);
uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_TX_BUF_LEN);
PIOS_Assert(rx_buffer);
PIOS_Assert(tx_buffer);
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_com_driver, pios_usb_hid_id,
rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN,
tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) {
PIOS_Assert(0);
}
#endif /* PIOS_INCLUDE_COM */
#endif /* PIOS_INCLUDE_USB_HID */
#endif /* PIOS_INCLUDE_USB_HID */
#if defined(PIOS_INCLUDE_I2C)
if (PIOS_I2C_Init(&pios_i2c_main_adapter_id, &pios_i2c_main_adapter_cfg)) {

View File

@ -29,6 +29,17 @@
#include <openpilot.h>
#include <uavobjectsinit.h>
#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;
void Stack_Change() {
}
void Stack_Change_Weak() {
}
/**
* PIOS_Board_Init()
* initializes all the core systems on this specific hardware

View File

@ -38,11 +38,21 @@
* and we cannot define a linker script for each of them atm
*/
typedef int32_t (*initcall_t)(void);
typedef struct {
initcall_t fn_minit;
initcall_t fn_tinit;
} initmodule_t;
/* Init module section */
extern initmodule_t __module_initcall_start[], __module_initcall_end[];
extern void InitModules();
extern void StartModules();
#define UAVOBJ_INITCALL(fn)
#define MODULE_INITCALL(ifn, iparam, sfn, sparam, flags)
#define MODULE_INITCALL(ifn, sfn)
#define MODULE_TASKCREATE_ALL { \
/* Start all module threads */ \

View File

@ -0,0 +1,54 @@
/**
******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_RCVR RCVR layer functions
* @brief Hardware communication layer
* @{
*
* @file pios_rcvr.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief RCVR layer functions header
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PIOS_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);
};
/* Public Functions */
extern int32_t PIOS_RCVR_Read(uint32_t rcvr_id, uint8_t channel);
#endif /* PIOS_RCVR_H */
/**
* @}
* @}
*/

View File

@ -0,0 +1,48 @@
/**
******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_RCVR RCVR Functions
* @brief PIOS interface for RCVR drivers
* @{
*
* @file pios_rcvr_priv.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Thorsten Klose (tk@midibox.org)
* @brief USART private definitions.
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PIOS_RCVR_PRIV_H
#define PIOS_RCVR_PRIV_H
#include <pios.h>
extern uint32_t pios_rcvr_max_channel;
extern int32_t PIOS_RCVR_Init(uint32_t * rcvr_id, const struct pios_rcvr_driver * driver, const uint32_t lower_id);
extern void PIOS_RCVR_IRQ_Handler(uint32_t rcvr_id);
#endif /* PIOS_RCVR_PRIV_H */
/**
* @}
* @}
*/

View File

@ -65,6 +65,7 @@
#include <pios_wdg.h>
#include <pios_debug.h>
#include <pios_crc.h>
#include <pios_rcvr.h>
#define NELEMENTS(x) (sizeof(x) / sizeof(*(x)))

View File

@ -67,10 +67,6 @@ int32_t PIOS_DELAY_WaituS(uint16_t uS)
while (!nanosleep(&wait,&rest)) {
wait=rest;
}
//uint16_t start = PIOS_DELAY_TIMER->CNT;
/* Note that this event works on 16bit counter wrap-arounds */
//while((uint16_t)(PIOS_DELAY_TIMER->CNT - start) <= uS);
/* No error */
return 0;

View File

@ -0,0 +1,100 @@
/* Project Includes */
#include "pios.h"
#if defined(PIOS_INCLUDE_RCVR)
#include <pios_rcvr_priv.h>
enum pios_rcvr_dev_magic {
PIOS_RCVR_DEV_MAGIC = 0x99aabbcc,
};
struct pios_rcvr_dev {
enum pios_rcvr_dev_magic magic;
uint32_t lower_id;
const struct pios_rcvr_driver * driver;
};
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
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));
if (!rcvr_dev) return (NULL);
rcvr_dev->magic = PIOS_RCVR_DEV_MAGIC;
return(rcvr_dev);
}
#else
static struct pios_rcvr_dev pios_rcvr_devs[PIOS_RCVR_MAX_DEVS];
static uint8_t pios_rcvr_num_devs;
static struct pios_rcvr_dev * PIOS_RCVR_alloc(void)
{
struct pios_rcvr_dev * rcvr_dev;
if (pios_rcvr_num_devs >= PIOS_RCVR_MAX_DEVS) {
return (NULL);
}
rcvr_dev = &pios_rcvr_devs[pios_rcvr_num_devs++];
rcvr_dev->magic = PIOS_RCVR_DEV_MAGIC;
return (rcvr_dev);
}
#endif
/**
* Initialises RCVR layer
* \param[out] handle
* \param[in] driver
* \param[in] id
* \return < 0 if initialisation failed
*/
int32_t PIOS_RCVR_Init(uint32_t * rcvr_id, const struct pios_rcvr_driver * driver, const uint32_t lower_id)
{
PIOS_DEBUG_Assert(rcvr_id);
PIOS_DEBUG_Assert(driver);
struct pios_rcvr_dev * rcvr_dev;
rcvr_dev = (struct pios_rcvr_dev *) PIOS_RCVR_alloc();
if (!rcvr_dev) goto out_fail;
rcvr_dev->driver = driver;
rcvr_dev->lower_id = lower_id;
*rcvr_id = pios_rcvr_num_devs - 1;
return(0);
out_fail:
return(-1);
}
int32_t PIOS_RCVR_Read(uint32_t rcvr_id, uint8_t channel)
{
struct pios_rcvr_dev * rcvr_dev = &pios_rcvr_devs[rcvr_id];
if (!PIOS_RCVR_validate(rcvr_dev)) {
/* Undefined RCVR port for this board (see pios_board.c) */
PIOS_DEBUG_Assert(0);
}
PIOS_DEBUG_Assert(rcvr_dev->driver->read);
return rcvr_dev->driver->read(rcvr_dev->lower_id, channel);
}
#endif
/**
* @}
* @}
*/

View File

@ -62,11 +62,7 @@ int32_t PIOS_DELAY_Init(void)
int32_t PIOS_DELAY_WaituS(uint16_t uS)
{
Sleep(uS/1000);
//uint16_t start = PIOS_DELAY_TIMER->CNT;
/* Note that this event works on 16bit counter wrap-arounds */
//while((uint16_t)(PIOS_DELAY_TIMER->CNT - start) <= uS);
/* No error */
return 0;
}

View File

@ -79,12 +79,6 @@ TIM8 | | | |
#define PIOS_LED_PINS { PIOS_LED_LED1_GPIO_PIN }
#define PIOS_LED_CLKS { PIOS_LED_LED1_GPIO_CLK }
//-------------------------
// Delay Timer
//-------------------------
#define PIOS_DELAY_TIMER TIM2
#define PIOS_DELAY_TIMER_RCC_FUNC RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE)
//-------------------------
// System Settings
//-------------------------
@ -118,8 +112,6 @@ extern uint32_t pios_i2c_main_adapter_id;
// PIOS_USART
//-------------------------
#define PIOS_USART_MAX_DEVS 2
#define PIOS_USART_RX_BUFFER_SIZE 256
#define PIOS_USART_TX_BUFFER_SIZE 256
//-------------------------
// PIOS_COM
@ -127,6 +119,7 @@ extern uint32_t pios_i2c_main_adapter_id;
// See also pios_board.c
//-------------------------
#define PIOS_COM_MAX_DEVS 2
extern uint32_t pios_com_aux_id;
#define PIOS_COM_AUX (pios_com_aux_id)
#define PIOS_COM_DEBUG PIOS_COM_AUX

View File

@ -91,12 +91,6 @@ TIM4 | RC In 1 | Servo 3 | Servo 2 | Servo 1
#define PIOS_LED_PINS { PIOS_LED_LED1_GPIO_PIN }
#define PIOS_LED_CLKS { PIOS_LED_LED1_GPIO_CLK }
//-------------------------
// Delay Timer
//-------------------------
#define PIOS_DELAY_TIMER TIM3
#define PIOS_DELAY_TIMER_RCC_FUNC RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE)
//-------------------------
// System Settings
//-------------------------
@ -131,15 +125,12 @@ extern uint32_t pios_i2c_main_adapter_id;
//-------------------------
#define PIOS_USART_MAX_DEVS 2
#define PIOS_USART_RX_BUFFER_SIZE 256
#define PIOS_USART_TX_BUFFER_SIZE 256
//-------------------------
// PIOS_COM
//
// See also pios_board.c
//-------------------------
#define PIOS_COM_MAX_DEVS 4
#define PIOS_COM_MAX_DEVS 3
extern uint32_t pios_com_telem_rf_id;
#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id)
@ -153,16 +144,6 @@ extern uint32_t pios_com_gps_id;
extern uint32_t pios_com_telem_usb_id;
#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id)
#ifdef PIOS_INCLUDE_SPEKTRUM
extern uint32_t pios_com_spektrum_id;
#define PIOS_COM_SPEKTRUM (pios_com_spektrum_id)
#endif
#ifdef PIOS_INCLUDE_SBUS
extern uint32_t pios_com_sbus_id;
#define PIOS_COM_SBUS (pios_com_sbus_id)
#endif
//-------------------------
// ADC
// PIOS_ADC_PinGet(0) = Gyro Z
@ -231,7 +212,7 @@ extern uint32_t pios_com_sbus_id;
//-------------------------
// Receiver PPM input
//-------------------------
#define PIOS_PPM_NUM_INPUTS 6 //Could be more if needed
#define PIOS_PPM_NUM_INPUTS 12
//-------------------------
// Receiver PWM input
@ -271,10 +252,9 @@ extern uint32_t pios_com_sbus_id;
// USB
//-------------------------
#define PIOS_USB_ENABLED 1
#define PIOS_USB_HID_MAX_DEVS 1
#define PIOS_USB_DETECT_GPIO_PORT GPIOC
#define PIOS_USB_DETECT_GPIO_PIN GPIO_Pin_15
#define PIOS_USB_DETECT_EXTI_LINE EXTI_Line15
#define PIOS_IRQ_USB_PRIORITY PIOS_IRQ_PRIO_MID
#define PIOS_USB_RX_BUFFER_SIZE 128
#define PIOS_USB_TX_BUFFER_SIZE 256
#endif /* STM32103CB_AHRS_H_ */

View File

@ -117,14 +117,6 @@ TIM4 | STOPWATCH |
#define TX_LED_OFF PIOS_LED_Off(LED4)
#define TX_LED_TOGGLE PIOS_LED_Toggle(LED4)
// *****************************************************************
// Delay Timer
//#define PIOS_DELAY_TIMER TIM2
//#define PIOS_DELAY_TIMER_RCC_FUNC RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE)
#define PIOS_DELAY_TIMER TIM1
#define PIOS_DELAY_TIMER_RCC_FUNC RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1, ENABLE)
// *****************************************************************
// Timer interrupt
@ -152,9 +144,6 @@ extern uint32_t pios_spi_port_id;
//-------------------------
#define PIOS_USART_MAX_DEVS 1
#define PIOS_USART_RX_BUFFER_SIZE 512
#define PIOS_USART_TX_BUFFER_SIZE 512
//-------------------------
// PIOS_COM
//
@ -404,12 +393,11 @@ extern uint32_t pios_com_telem_usb_id;
#if defined(PIOS_INCLUDE_USB_HID)
#define PIOS_USB_ENABLED 1
#define PIOS_USB_HID_MAX_DEVS 1
#define PIOS_USB_DETECT_GPIO_PORT GPIO_IN_2_PORT
#define PIOS_USB_DETECT_GPIO_PIN GPIO_IN_2_PIN
#define PIOS_USB_DETECT_EXTI_LINE EXTI_Line4
#define PIOS_IRQ_USB_PRIORITY 8
#define PIOS_USB_RX_BUFFER_SIZE 512
#define PIOS_USB_TX_BUFFER_SIZE 512
#endif
// *****************************************************************

View File

@ -125,9 +125,6 @@ extern uint32_t pios_i2c_gyro_adapter_id;
//-------------------------
#define PIOS_USART_MAX_DEVS 2
#define PIOS_USART_RX_BUFFER_SIZE 256
#define PIOS_USART_TX_BUFFER_SIZE 256
//-------------------------
// PIOS_COM
//
@ -144,12 +141,6 @@ extern uint32_t pios_com_aux_id;
#define PIOS_COM_DEBUG PIOS_COM_AUX
#endif
//-------------------------
// Delay Timer
//-------------------------
#define PIOS_DELAY_TIMER TIM2
#define PIOS_DELAY_TIMER_RCC_FUNC RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE)
//-------------------------
// System Settings
//-------------------------

View File

@ -139,9 +139,6 @@ extern uint32_t pios_i2c_main_adapter_id;
//-------------------------
#define PIOS_USART_MAX_DEVS 3
#define PIOS_USART_RX_BUFFER_SIZE 512
#define PIOS_USART_TX_BUFFER_SIZE 512
//-------------------------
// PIOS_COM
//
@ -164,22 +161,6 @@ extern uint32_t pios_com_aux_id;
#define PIOS_COM_DEBUG PIOS_COM_AUX
#endif
#ifdef PIOS_INCLUDE_SPEKTRUM
extern uint32_t pios_com_spektrum_id;
#define PIOS_COM_SPEKTRUM (pios_com_spektrum_id)
#endif
#ifdef PIOS_INCLUDE_SBUS
extern uint32_t pios_com_sbus_id;
#define PIOS_COM_SBUS (pios_com_sbus_id)
#endif
//-------------------------
// Delay Timer
//-------------------------
#define PIOS_DELAY_TIMER TIM2
#define PIOS_DELAY_TIMER_RCC_FUNC RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE)
//-------------------------
// System Settings
//-------------------------
@ -204,8 +185,7 @@ extern uint32_t pios_com_sbus_id;
//-------------------------
// Receiver PPM input
//-------------------------
#define PIOS_PPM_NUM_INPUTS 8 //Could be more if needed
#define PIOS_PPM_SUPV_ENABLED 1
#define PIOS_PPM_NUM_INPUTS 12
//-------------------------
// Receiver PWM input
@ -315,12 +295,11 @@ extern uint32_t pios_com_sbus_id;
// USB
//-------------------------
#define PIOS_USB_ENABLED 1
#define PIOS_USB_HID_MAX_DEVS 1
#define PIOS_USB_DETECT_GPIO_PORT GPIOC
#define PIOS_USB_DETECT_GPIO_PIN GPIO_Pin_4
#define PIOS_USB_DETECT_EXTI_LINE EXTI_Line4
#define PIOS_IRQ_USB_PRIORITY PIOS_IRQ_PRIO_MID
#define PIOS_USB_RX_BUFFER_SIZE 512
#define PIOS_USB_TX_BUFFER_SIZE 512
/**
* glue macros for file IO

View File

@ -34,8 +34,34 @@
#if defined(PIOS_INCLUDE_COM)
#include "fifo_buffer.h"
#include <pios_com_priv.h>
#if !defined(PIOS_INCLUDE_FREERTOS)
#include "pios_delay.h" /* PIOS_DELAY_WaitmS */
#endif
enum pios_com_dev_magic {
PIOS_COM_DEV_MAGIC = 0xaa55aa55,
};
struct pios_com_dev {
enum pios_com_dev_magic magic;
uint32_t lower_id;
const struct pios_com_driver * driver;
#if defined(PIOS_INCLUDE_FREERTOS)
xSemaphoreHandle tx_sem;
xSemaphoreHandle rx_sem;
#endif
bool has_rx;
bool has_tx;
t_fifo_buffer rx;
t_fifo_buffer tx;
};
static bool PIOS_COM_validate(struct pios_com_dev * com_dev)
{
return (com_dev && (com_dev->magic == PIOS_COM_DEV_MAGIC));
@ -70,6 +96,11 @@ static struct pios_com_dev * PIOS_COM_alloc(void)
}
#endif
static uint16_t PIOS_COM_TxOutCallback(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, bool * need_yield);
static uint16_t PIOS_COM_RxInCallback(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, bool * need_yield);
static void PIOS_COM_UnblockRx(struct pios_com_dev * com_dev, bool * need_yield);
static void PIOS_COM_UnblockTx(struct pios_com_dev * com_dev, bool * need_yield);
/**
* Initialises COM layer
* \param[out] handle
@ -77,18 +108,48 @@ static struct pios_com_dev * PIOS_COM_alloc(void)
* \param[in] id
* \return < 0 if initialisation failed
*/
int32_t PIOS_COM_Init(uint32_t * com_id, const struct pios_com_driver * driver, const uint32_t lower_id)
int32_t PIOS_COM_Init(uint32_t * com_id, const struct pios_com_driver * driver, uint32_t lower_id, uint8_t * rx_buffer, uint16_t rx_buffer_len, uint8_t * tx_buffer, uint16_t tx_buffer_len)
{
PIOS_DEBUG_Assert(com_id);
PIOS_DEBUG_Assert(driver);
PIOS_Assert(com_id);
PIOS_Assert(driver);
bool has_rx = (rx_buffer && rx_buffer_len > 0);
bool has_tx = (tx_buffer && tx_buffer_len > 0);
PIOS_Assert(has_rx || has_tx);
PIOS_Assert(driver->bind_tx_cb || !has_tx);
PIOS_Assert(driver->bind_rx_cb || !has_rx);
struct pios_com_dev * com_dev;
com_dev = (struct pios_com_dev *) PIOS_COM_alloc();
if (!com_dev) goto out_fail;
com_dev->driver = driver;
com_dev->id = lower_id;
com_dev->driver = driver;
com_dev->lower_id = lower_id;
com_dev->has_rx = has_rx;
com_dev->has_tx = has_tx;
if (has_rx) {
fifoBuf_init(&com_dev->rx, rx_buffer, rx_buffer_len);
#if defined(PIOS_INCLUDE_FREERTOS)
vSemaphoreCreateBinary(com_dev->rx_sem);
#endif /* PIOS_INCLUDE_FREERTOS */
(com_dev->driver->bind_rx_cb)(lower_id, PIOS_COM_RxInCallback, (uint32_t)com_dev);
if (com_dev->driver->rx_start) {
/* Start the receiver */
(com_dev->driver->rx_start)(com_dev->lower_id,
fifoBuf_getFree(&com_dev->rx));
}
}
if (has_tx) {
fifoBuf_init(&com_dev->tx, tx_buffer, tx_buffer_len);
#if defined(PIOS_INCLUDE_FREERTOS)
vSemaphoreCreateBinary(com_dev->tx_sem);
#endif /* PIOS_INCLUDE_FREERTOS */
(com_dev->driver->bind_tx_cb)(lower_id, PIOS_COM_TxOutCallback, (uint32_t)com_dev);
}
*com_id = (uint32_t)com_dev;
return(0);
@ -97,6 +158,88 @@ out_fail:
return(-1);
}
static void PIOS_COM_UnblockRx(struct pios_com_dev * com_dev, bool * need_yield)
{
#if defined(PIOS_INCLUDE_FREERTOS)
static signed portBASE_TYPE xHigherPriorityTaskWoken;
xSemaphoreGiveFromISR(com_dev->rx_sem, &xHigherPriorityTaskWoken);
if (xHigherPriorityTaskWoken != pdFALSE) {
*need_yield = true;
} else {
*need_yield = false;
}
#else
*need_yield = false;
#endif
}
static void PIOS_COM_UnblockTx(struct pios_com_dev * com_dev, bool * need_yield)
{
#if defined(PIOS_INCLUDE_FREERTOS)
static signed portBASE_TYPE xHigherPriorityTaskWoken;
xSemaphoreGiveFromISR(com_dev->tx_sem, &xHigherPriorityTaskWoken);
if (xHigherPriorityTaskWoken != pdFALSE) {
*need_yield = true;
} else {
*need_yield = false;
}
#else
*need_yield = false;
#endif
}
static uint16_t PIOS_COM_RxInCallback(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, bool * need_yield)
{
struct pios_com_dev * com_dev = (struct pios_com_dev *)context;
bool valid = PIOS_COM_validate(com_dev);
PIOS_Assert(valid);
PIOS_Assert(com_dev->has_rx);
PIOS_IRQ_Disable();
uint16_t bytes_into_fifo = fifoBuf_putData(&com_dev->rx, buf, buf_len);
PIOS_IRQ_Enable();
if (bytes_into_fifo > 0) {
/* Data has been added to the buffer */
PIOS_COM_UnblockRx(com_dev, need_yield);
}
if (headroom) {
*headroom = fifoBuf_getFree(&com_dev->rx);
}
return (bytes_into_fifo);
}
static uint16_t PIOS_COM_TxOutCallback(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, bool * need_yield)
{
struct pios_com_dev * com_dev = (struct pios_com_dev *)context;
bool valid = PIOS_COM_validate(com_dev);
PIOS_Assert(valid);
PIOS_Assert(buf);
PIOS_Assert(buf_len);
PIOS_Assert(com_dev->has_tx);
PIOS_IRQ_Disable();
uint16_t bytes_from_fifo = fifoBuf_getData(&com_dev->tx, buf, buf_len);
PIOS_IRQ_Enable();
if (bytes_from_fifo > 0) {
/* More space has been made in the buffer */
PIOS_COM_UnblockTx(com_dev, need_yield);
}
if (headroom) {
*headroom = fifoBuf_getUsed(&com_dev->tx);
}
return (bytes_from_fifo);
}
/**
* Change the port speed without re-initializing
* \param[in] port COM port
@ -115,7 +258,7 @@ int32_t PIOS_COM_ChangeBaud(uint32_t com_id, uint32_t baud)
/* Invoke the driver function if it exists */
if (com_dev->driver->set_baud) {
com_dev->driver->set_baud(com_dev->id, baud);
com_dev->driver->set_baud(com_dev->lower_id, baud);
}
return 0;
@ -140,12 +283,26 @@ int32_t PIOS_COM_SendBufferNonBlocking(uint32_t com_id, const uint8_t *buffer, u
return -1;
}
/* Invoke the driver function if it exists */
if (com_dev->driver->tx_nb) {
return com_dev->driver->tx_nb(com_dev->id, buffer, len);
PIOS_Assert(com_dev->has_tx);
if (len >= fifoBuf_getFree(&com_dev->tx)) {
/* Buffer cannot accept all requested bytes (retry) */
return -2;
}
return 0;
PIOS_IRQ_Disable();
uint16_t bytes_into_fifo = fifoBuf_putData(&com_dev->tx, buffer, len);
PIOS_IRQ_Enable();
if (bytes_into_fifo > 0) {
/* More data has been put in the tx buffer, make sure the tx is started */
if (com_dev->driver->tx_start) {
com_dev->driver->tx_start(com_dev->lower_id,
fifoBuf_getUsed(&com_dev->tx));
}
}
return (0);
}
/**
@ -166,12 +323,27 @@ int32_t PIOS_COM_SendBuffer(uint32_t com_id, const uint8_t *buffer, uint16_t len
return -1;
}
/* Invoke the driver function if it exists */
if (com_dev->driver->tx) {
return com_dev->driver->tx(com_dev->id, buffer, len);
}
PIOS_Assert(com_dev->has_tx);
return 0;
int32_t rc;
do {
rc = PIOS_COM_SendBufferNonBlocking(com_id, buffer, len);
#if defined(PIOS_INCLUDE_FREERTOS)
if (rc == -2) {
/* Make sure the transmitter is running while we wait */
if (com_dev->driver->tx_start) {
(com_dev->driver->tx_start)(com_dev->lower_id,
fifoBuf_getUsed(&com_dev->tx));
}
if (xSemaphoreTake(com_dev->tx_sem, portMAX_DELAY) != pdTRUE) {
return -3;
}
}
#endif
} while (rc == -2);
return rc;
}
/**
@ -273,18 +445,47 @@ int32_t PIOS_COM_SendFormattedString(uint32_t com_id, const char *format, ...)
* \param[in] port COM port
* \returns Byte from buffer
*/
uint8_t PIOS_COM_ReceiveBuffer(uint32_t com_id)
uint16_t PIOS_COM_ReceiveBuffer(uint32_t com_id, uint8_t * buf, uint16_t buf_len, uint32_t timeout_ms)
{
PIOS_Assert(buf);
PIOS_Assert(buf_len);
struct pios_com_dev * com_dev = (struct pios_com_dev *)com_id;
if (!PIOS_COM_validate(com_dev)) {
/* Undefined COM port for this board (see pios_board.c) */
PIOS_DEBUG_Assert(0);
PIOS_Assert(0);
}
PIOS_Assert(com_dev->has_rx);
check_again:
PIOS_IRQ_Disable();
uint16_t bytes_from_fifo = fifoBuf_getData(&com_dev->rx, buf, buf_len);
PIOS_IRQ_Enable();
if (bytes_from_fifo == 0 && timeout_ms > 0) {
/* No more bytes in receive buffer */
/* Make sure the receiver is running while we wait */
if (com_dev->driver->rx_start) {
/* Notify the lower layer that there is now room in the rx buffer */
(com_dev->driver->rx_start)(com_dev->lower_id,
fifoBuf_getFree(&com_dev->rx));
}
#if defined(PIOS_INCLUDE_FREERTOS)
if (xSemaphoreTake(com_dev->rx_sem, timeout_ms / portTICK_RATE_MS) == pdTRUE) {
/* Make sure we don't come back here again */
timeout_ms = 0;
goto check_again;
}
#else
PIOS_DELAY_WaitmS(1);
timeout_ms--;
goto check_again;
#endif
}
PIOS_DEBUG_Assert(com_dev->driver->rx);
return com_dev->driver->rx(com_dev->id);
/* Return received byte */
return (bytes_from_fifo);
}
/**
@ -298,16 +499,11 @@ int32_t PIOS_COM_ReceiveBufferUsed(uint32_t com_id)
if (!PIOS_COM_validate(com_dev)) {
/* Undefined COM port for this board (see pios_board.c) */
/* This is commented out so com_id=NULL can be used to disable telemetry */
//PIOS_DEBUG_Assert(0);
return 0;
PIOS_Assert(0);
}
if (!com_dev->driver->rx_avail) {
return 0;
}
return com_dev->driver->rx_avail(com_dev->id);
PIOS_Assert(com_dev->has_rx);
return (fifoBuf_getUsed(&com_dev->rx));
}
#endif

View File

@ -56,7 +56,7 @@ static struct pios_rcvr_dev * PIOS_RCVR_alloc(void)
* \param[in] id
* \return < 0 if initialisation failed
*/
int32_t PIOS_RCVR_Init(uint32_t * rcvr_id, const struct pios_rcvr_driver * driver, const uint32_t lower_id)
int32_t PIOS_RCVR_Init(uint32_t * rcvr_id, const struct pios_rcvr_driver * driver, uint32_t lower_id)
{
PIOS_DEBUG_Assert(rcvr_id);
PIOS_DEBUG_Assert(driver);
@ -82,7 +82,7 @@ int32_t PIOS_RCVR_Read(uint32_t rcvr_id, uint8_t channel)
if (!PIOS_RCVR_validate(rcvr_dev)) {
/* Undefined RCVR port for this board (see pios_board.c) */
PIOS_DEBUG_Assert(0);
PIOS_Assert(0);
}
PIOS_DEBUG_Assert(rcvr_dev->driver->read);

View File

@ -7,10 +7,10 @@
* @{
*
* @file pios_delay.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org)
* @author Michael Smith Copyright (C) 2011
* @brief Delay Functions
* - Provides a micro-second granular delay using a TIM
* - Provides a micro-second granular delay using the CPU
* cycle counter.
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
@ -31,72 +31,97 @@
*/
/* Project Includes */
#include "pios.h"
#include <pios.h>
#if defined(PIOS_INCLUDE_DELAY)
/* these should be defined by CMSIS, but they aren't */
#define DWT_CTRL (*(volatile uint32_t *)0xe0001000)
#define CYCCNTENA (1<<0)
#define DWT_CYCCNT (*(volatile uint32_t *)0xe0001004)
/* cycles per microsecond */
static uint32_t us_ticks;
/**
* Initialises the Timer used by PIOS_DELAY functions<BR>
* This is called from pios.c as part of the main() function
* at system start up.
* \return < 0 if initialisation failed
*/
* Initialises the Timer used by PIOS_DELAY functions.
*
* \return always zero (success)
*/
int32_t PIOS_DELAY_Init(void)
{
/* Enable timer clock */
PIOS_DELAY_TIMER_RCC_FUNC;
RCC_ClocksTypeDef clocks;
/* Time base configuration */
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
TIM_TimeBaseStructure.TIM_Period = 65535; // maximum value
TIM_TimeBaseStructure.TIM_Prescaler = 72 - 1; // for 1 uS accuracy fixed to 72Mhz
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
TIM_TimeBaseInit(PIOS_DELAY_TIMER, &TIM_TimeBaseStructure);
/* compute the number of system clocks per microsecond */
RCC_GetClocksFreq(&clocks);
us_ticks = clocks.SYSCLK_Frequency / 1000000;
PIOS_DEBUG_Assert(us_ticks > 1);
/* Enable counter */
TIM_Cmd(PIOS_DELAY_TIMER, ENABLE);
/* turn on access to the DWT registers */
CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk;
/* enable the CPU cycle counter */
DWT_CTRL |= CYCCNTENA;
return 0;
}
/**
* Waits for a specific number of uS
*
* Example:<BR>
* \code
* // Wait for 500 uS
* PIOS_DELAY_Wait_uS(500);
* \endcode
* \param[in] uS delay
* \return < 0 on errors
*/
int32_t PIOS_DELAY_WaituS(uint32_t uS)
{
uint32_t elapsed = 0;
uint32_t last_count = DWT_CYCCNT;
for (;;) {
uint32_t current_count = DWT_CYCCNT;
uint32_t elapsed_uS;
/* measure the time elapsed since the last time we checked */
elapsed += current_count - last_count;
last_count = current_count;
/* convert to microseconds */
elapsed_uS = elapsed / us_ticks;
if (elapsed_uS >= uS)
break;
/* reduce the delay by the elapsed time */
uS -= elapsed_uS;
/* keep fractional microseconds for the next iteration */
elapsed %= us_ticks;
}
/* No error */
return 0;
}
/**
* Waits for a specific number of uS<BR>
* Example:<BR>
* \code
* // Wait for 500 uS
* PIOS_DELAY_Wait_uS(500);
* \endcode
* \param[in] uS delay (1..65535 microseconds)
* \return < 0 on errors
*/
int32_t PIOS_DELAY_WaituS(uint16_t uS)
* Waits for a specific number of mS
*
* Example:<BR>
* \code
* // Wait for 500 mS
* PIOS_DELAY_Wait_mS(500);
* \endcode
* \param[in] mS delay
* \return < 0 on errors
*/
int32_t PIOS_DELAY_WaitmS(uint32_t mS)
{
uint16_t start = PIOS_DELAY_TIMER->CNT;
/* Note that this event works on 16bit counter wrap-arounds */
while ((uint16_t) (PIOS_DELAY_TIMER->CNT - start) <= uS) ;
/* No error */
return 0;
}
/**
* Waits for a specific number of mS<BR>
* Example:<BR>
* \code
* // Wait for 500 mS
* PIOS_DELAY_Wait_mS(500);
* \endcode
* \param[in] mS delay (1..65535 milliseconds)
* \return < 0 on errors
*/
int32_t PIOS_DELAY_WaitmS(uint16_t mS)
{
for (int i = 0; i < mS; i++) {
while (mS--) {
PIOS_DELAY_WaituS(1000);
}
@ -108,22 +133,19 @@ int32_t PIOS_DELAY_WaitmS(uint16_t mS)
* @brief Query the Delay timer for the current uS
* @return A microsecond value
*/
uint16_t PIOS_DELAY_GetuS()
uint32_t PIOS_DELAY_GetuS(void)
{
return PIOS_DELAY_TIMER->CNT;
return DWT_CYCCNT / us_ticks;
}
/**
* @brief Compute the difference between now and a reference time
* @param[in] the reference time to compare now to
* @return The number of uS since the delay
*
* @note the user is responsible for worrying about rollover on the 16 bit uS counter
* @brief Calculate time in microseconds since a previous time
* @param[in] t previous time
* @return time in us since previous time t.
*/
int32_t PIOS_DELAY_DiffuS(uint16_t ref)
uint32_t PIOS_DELAY_GetuSSince(uint32_t t)
{
int32_t ret_t = ref;
return (int16_t) (PIOS_DELAY_GetuS() - ret_t);
return (PIOS_DELAY_GetuS() - t);
}
#endif

View File

@ -41,19 +41,30 @@ const struct pios_rcvr_driver pios_ppm_rcvr_driver = {
.read = PIOS_PPM_Get,
};
#define PIOS_PPM_IN_MIN_NUM_CHANNELS 4
#define PIOS_PPM_IN_MAX_NUM_CHANNELS PIOS_PPM_NUM_INPUTS
#define PIOS_PPM_STABLE_CHANNEL_COUNT 25 // frames
#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 PreviousValue;
static uint32_t CurrentValue;
static uint32_t CapturedValue;
static uint32_t CaptureValue[PIOS_PPM_NUM_INPUTS];
static uint32_t CapCounter[PIOS_PPM_NUM_INPUTS];
static uint16_t TimerCounter;
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 uint8_t SupervisorState = 0;
static uint32_t CapCounterPrev[PIOS_PPM_NUM_INPUTS];
static bool Tracking;
static bool Fresh;
static void PIOS_PPM_Supervisor(uint32_t ppm_id);
@ -63,13 +74,19 @@ void PIOS_PPM_Init(void)
int32_t i;
PulseIndex = 0;
PreviousValue = 0;
CurrentValue = 0;
CapturedValue = 0;
TimerCounter = 0;
PreviousTime = 0;
CurrentTime = 0;
DeltaTime = 0;
LargeCounter = 0;
NumChannels = -1;
NumChannelsPrevFrame = -1;
NumChannelCounter = 0;
Tracking = FALSE;
Fresh = FALSE;
for (i = 0; i < PIOS_PPM_NUM_INPUTS; i++) {
for (i = 0; i < PIOS_PPM_IN_MAX_NUM_CHANNELS; i++) {
CaptureValue[i] = 0;
CaptureValueNewFrame[i] = 0;
}
NVIC_InitTypeDef NVIC_InitStructure = pios_ppm_cfg.irq.init;
@ -93,7 +110,6 @@ void PIOS_PPM_Init(void)
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);
@ -134,15 +150,6 @@ void PIOS_PPM_Init(void)
/* Enable timers */
TIM_Cmd(pios_ppm_cfg.timer, ENABLE);
/* Supervisor Setup */
/* Flush counter variables */
for (i = 0; i < PIOS_PPM_NUM_INPUTS; i++) {
CapCounter[i] = 0;
}
for (i = 0; i < PIOS_PPM_NUM_INPUTS; i++) {
CapCounterPrev[i] = 0;
}
/* Setup local variable which stays in this scope */
/* Doing this here and using a local variable saves doing it in the ISR */
TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI;
@ -163,7 +170,7 @@ 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_NUM_INPUTS) {
if (channel >= PIOS_PPM_IN_MAX_NUM_CHANNELS) {
return -1;
}
return CaptureValue[channel];
@ -176,56 +183,103 @@ static int32_t PIOS_PPM_Get(uint32_t rcvr_id, uint8_t channel)
*/
void PIOS_PPM_irq_handler(void)
{
/* 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.
*/
if (TIM_GetITStatus(pios_ppm_cfg.timer, TIM_IT_Update) == SET) {
TimerCounter+=pios_ppm_cfg.timer->ARR;
/* Clear TIMx overflow interrupt pending bit */
TIM_ClearITPendingBit(pios_ppm_cfg.timer, TIM_IT_Update);
if (TIM_GetITStatus(pios_ppm_cfg.timer, pios_ppm_cfg.ccr) != SET) {
return;
}
/* 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;
}
/* Do this as it's more efficient */
/* Signal edge interrupt */
if (TIM_GetITStatus(pios_ppm_cfg.timer, pios_ppm_cfg.ccr) == SET) {
PreviousValue = CurrentValue;
PreviousTime = CurrentTime;
switch((int32_t) pios_ppm_cfg.ccr) {
case (int32_t)TIM_IT_CC1:
CurrentValue = TIM_GetCapture1(pios_ppm_cfg.timer);
CurrentTime = TIM_GetCapture1(pios_ppm_cfg.timer);
break;
case (int32_t)TIM_IT_CC2:
CurrentValue = TIM_GetCapture2(pios_ppm_cfg.timer);
CurrentTime = TIM_GetCapture2(pios_ppm_cfg.timer);
break;
case (int32_t)TIM_IT_CC3:
CurrentValue = TIM_GetCapture3(pios_ppm_cfg.timer);
CurrentTime = TIM_GetCapture3(pios_ppm_cfg.timer);
break;
case (int32_t)TIM_IT_CC4:
CurrentValue = TIM_GetCapture4(pios_ppm_cfg.timer);
CurrentTime = TIM_GetCapture4(pios_ppm_cfg.timer);
break;
}
CurrentValue+=TimerCounter;
if(CurrentValue > 0xFFFF) {
CurrentValue-=0xFFFF;
}
/* Clear TIMx Capture compare interrupt pending bit */
TIM_ClearITPendingBit(pios_ppm_cfg.timer, pios_ppm_cfg.ccr);
/* Capture computation */
if (CurrentValue > PreviousValue) {
CapturedValue = (CurrentValue - PreviousValue);
} else {
CapturedValue = ((0xFFFF - PreviousValue) + CurrentValue);
}
/* Convert to 32-bit timer result */
CurrentTime = CurrentTime + LargeCounter;
/* sync pulse */
if (CapturedValue > 8000) {
/* 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 (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;
}
}
Fresh = TRUE;
Tracking = TRUE;
NumChannelsPrevFrame = PulseIndex;
PulseIndex = 0;
/* trying to detect bad pulses, not sure this is working correctly yet. I need a scope :P */
} else if (CapturedValue > 750 && CapturedValue < 2500) {
if (PulseIndex < PIOS_PPM_NUM_INPUTS) {
CaptureValue[PulseIndex] = CapturedValue;
CapCounter[PulseIndex]++;
/* 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;
}
}
}
}
@ -241,26 +295,16 @@ static void PIOS_PPM_Supervisor(uint32_t ppm_id) {
}
supv_timer = 0;
/* Simple state machine */
if (SupervisorState == 0) {
/* Save this states values */
for (int32_t i = 0; i < PIOS_PPM_NUM_INPUTS; i++) {
CapCounterPrev[i] = CapCounter[i];
}
if (!Fresh) {
Tracking = FALSE;
/* Move to next state */
SupervisorState = 1;
} else {
/* See what channels have been updated */
for (int32_t i = 0; i < PIOS_PPM_NUM_INPUTS; i++) {
if (CapCounter[i] == CapCounterPrev[i]) {
CaptureValue[i] = 0;
}
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;
}
/* Move to next state */
SupervisorState = 0;
}
Fresh = FALSE;
}
#endif

View File

@ -35,7 +35,7 @@
#if defined(PIOS_INCLUDE_PWM)
/* Provide a RCVR driver */
static int32_t PIOS_PWM_Get(uint32_t rcvr_id, uint8_t chan_id);
static int32_t PIOS_PWM_Get(uint32_t rcvr_id, uint8_t channel);
const struct pios_rcvr_driver pios_pwm_rcvr_driver = {
.read = PIOS_PWM_Get,

View File

@ -132,10 +132,30 @@ static void process_byte(uint8_t b)
}
}
static uint16_t PIOS_SBUS_RxInCallback(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, bool * need_yield)
{
/* process byte(s) and clear receive timer */
for (uint8_t i = 0; i < buf_len; i++) {
process_byte(buf[i]);
receive_timer = 0;
}
/* Always signal that we can accept another byte */
if (headroom) {
*headroom = SBUS_FRAME_LENGTH;
}
/* We never need a yield */
*need_yield = false;
/* Always indicate that all bytes were consumed */
return (buf_len);
}
/**
* Initialise S.Bus receiver interface
*/
void PIOS_SBUS_Init(const struct pios_sbus_cfg *cfg)
int32_t PIOS_SBUS_Init(uint32_t * sbus_id, const struct pios_sbus_cfg *cfg, const struct pios_com_driver * driver, uint32_t lower_id)
{
/* Enable inverter clock and enable the inverter */
(*cfg->gpio_clk_func)(cfg->gpio_clk_periph, ENABLE);
@ -144,9 +164,13 @@ void PIOS_SBUS_Init(const struct pios_sbus_cfg *cfg)
cfg->inv.init.GPIO_Pin,
cfg->gpio_inv_enable);
(driver->bind_rx_cb)(lower_id, PIOS_SBUS_RxInCallback, 0);
if (!PIOS_RTC_RegisterTickCallback(PIOS_SBUS_Supervisor, 0)) {
PIOS_Assert(0);
}
return (0);
}
/**
@ -164,34 +188,6 @@ static int32_t PIOS_SBUS_Get(uint32_t rcvr_id, uint8_t channel)
return channel_data[channel];
}
/**
* Interrupt handler for USART
*/
void PIOS_SBUS_irq_handler(uint32_t usart_id)
{
/* Grab the config for this device from the underlying USART device */
const struct pios_usart_cfg * cfg;
cfg = PIOS_USART_GetConfig(usart_id);
PIOS_Assert(cfg);
/* by always reading DR after SR make sure to clear any error interrupts */
volatile uint16_t sr = cfg->regs->SR;
volatile uint8_t b = cfg->regs->DR;
/* process received byte if one has arrived */
if (sr & USART_SR_RXNE) {
/* process byte and clear receive timer */
process_byte(b);
receive_timer = 0;
}
/* ignore TXE interrupts */
if (sr & USART_SR_TXE) {
/* disable TXE interrupt (TXEIE=0) */
USART_ITConfig(cfg->regs, USART_IT_TXE, DISABLE);
}
}
/**
* Input data supervisor is called periodically and provides
* two functions: frame syncing and failsafe triggering.

View File

@ -60,20 +60,45 @@ uint16_t supv_timer=0;
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 uint16_t PIOS_SPEKTRUM_RxInCallback(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, bool * need_yield)
{
/* process byte(s) and clear receive timer */
for (uint8_t i = 0; i < buf_len; i++) {
PIOS_SPEKTRUM_Decode(buf[i]);
supv_timer = 0;
}
/* Always signal that we can accept another byte */
if (headroom) {
*headroom = 1;
}
/* We never need a yield */
*need_yield = false;
/* Always indicate that all bytes were consumed */
return (buf_len);
}
/**
* Bind and Initialise Spektrum satellite receiver
*/
void PIOS_SPEKTRUM_Init(const struct pios_spektrum_cfg * cfg, 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, bool bind)
{
// TODO: need setting flag for bind on next powerup
if (bind) {
PIOS_SPEKTRUM_Bind(cfg);
}
(driver->bind_rx_cb)(lower_id, PIOS_SPEKTRUM_RxInCallback, 0);
if (!PIOS_RTC_RegisterTickCallback(PIOS_SPEKTRUM_Supervisor, 0)) {
PIOS_DEBUG_Assert(0);
}
return (0);
}
/**
@ -204,32 +229,6 @@ static int32_t PIOS_SPEKTRUM_Decode(uint8_t b)
return 0;
}
/* Custom interrupt handler for USART */
void PIOS_SPEKTRUM_irq_handler(uint32_t usart_id) {
/* Grab the config for this device from the underlying USART device */
const struct pios_usart_cfg * cfg;
cfg = PIOS_USART_GetConfig(usart_id);
PIOS_Assert(cfg);
/* by always reading DR after SR make sure to clear any error interrupts */
volatile uint16_t sr = cfg->regs->SR;
volatile uint8_t b = cfg->regs->DR;
/* check if RXNE flag is set */
if (sr & USART_SR_RXNE) {
if (PIOS_SPEKTRUM_Decode(b) < 0) {
/* Here we could add some error handling */
}
}
if (sr & USART_SR_TXE) { // check if TXE flag is set
/* Disable TXE interrupt (TXEIE=0) */
USART_ITConfig(cfg->regs, USART_IT_TXE, DISABLE);
}
/* byte arrived so clear "watchdog" timer */
supv_timer=0;
}
/**
*@brief This function is called between frames and when a spektrum word hasnt been decoded for too long
*@brief clears the channel values

View File

@ -38,17 +38,17 @@
/* Provide a COM driver */
static void PIOS_USART_ChangeBaud(uint32_t usart_id, uint32_t baud);
static int32_t PIOS_USART_TxBufferPutMoreNonBlocking(uint32_t usart_id, const uint8_t *buffer, uint16_t len);
static int32_t PIOS_USART_TxBufferPutMore(uint32_t usart_id, const uint8_t *buffer, uint16_t len);
static int32_t PIOS_USART_RxBufferGet(uint32_t usart_id);
static int32_t PIOS_USART_RxBufferUsed(uint32_t usart_id);
static void PIOS_USART_RegisterRxCallback(uint32_t usart_id, pios_com_callback rx_in_cb, uint32_t context);
static void PIOS_USART_RegisterTxCallback(uint32_t usart_id, pios_com_callback tx_out_cb, uint32_t context);
static void PIOS_USART_TxStart(uint32_t usart_id, uint16_t tx_bytes_avail);
static void PIOS_USART_RxStart(uint32_t usart_id, uint16_t rx_bytes_avail);
const struct pios_com_driver pios_usart_com_driver = {
.set_baud = PIOS_USART_ChangeBaud,
.tx_nb = PIOS_USART_TxBufferPutMoreNonBlocking,
.tx = PIOS_USART_TxBufferPutMore,
.rx = PIOS_USART_RxBufferGet,
.rx_avail = PIOS_USART_RxBufferUsed,
.set_baud = PIOS_USART_ChangeBaud,
.tx_start = PIOS_USART_TxStart,
.rx_start = PIOS_USART_RxStart,
.bind_tx_cb = PIOS_USART_RegisterTxCallback,
.bind_rx_cb = PIOS_USART_RegisterRxCallback,
};
enum pios_usart_dev_magic {
@ -59,13 +59,10 @@ struct pios_usart_dev {
enum pios_usart_dev_magic magic;
const struct pios_usart_cfg * cfg;
// align to 32-bit to try and provide speed improvement;
uint8_t rx_buffer[PIOS_USART_RX_BUFFER_SIZE] __attribute__ ((aligned(4)));
t_fifo_buffer rx;
// align to 32-bit to try and provide speed improvement;
uint8_t tx_buffer[PIOS_USART_TX_BUFFER_SIZE] __attribute__ ((aligned(4)));
t_fifo_buffer tx;
pios_com_callback rx_in_cb;
uint32_t rx_in_context;
pios_com_callback tx_out_cb;
uint32_t tx_out_context;
};
static bool PIOS_USART_validate(struct pios_usart_dev * usart_dev)
@ -147,10 +144,6 @@ int32_t PIOS_USART_Init(uint32_t * usart_id, const struct pios_usart_cfg * cfg)
/* Bind the configuration to the device instance */
usart_dev->cfg = cfg;
/* Clear buffer counters */
fifoBuf_init(&usart_dev->rx, usart_dev->rx_buffer, sizeof(usart_dev->rx_buffer));
fifoBuf_init(&usart_dev->tx, usart_dev->tx_buffer, sizeof(usart_dev->tx_buffer));
/* Enable the USART Pins Software Remapping */
if (usart_dev->cfg->remap) {
GPIO_PinRemapConfig(usart_dev->cfg->remap, ENABLE);
@ -203,17 +196,23 @@ out_fail:
return(-1);
}
const struct pios_usart_cfg * PIOS_USART_GetConfig(uint32_t usart_id)
static void PIOS_USART_RxStart(uint32_t usart_id, uint16_t rx_bytes_avail)
{
struct pios_usart_dev * usart_dev = (struct pios_usart_dev *)usart_id;
bool valid = PIOS_USART_validate(usart_dev);
PIOS_Assert(valid);
if (!valid) {
return (NULL);
}
USART_ITConfig(usart_dev->cfg->regs, USART_IT_RXNE, ENABLE);
}
static void PIOS_USART_TxStart(uint32_t usart_id, uint16_t tx_bytes_avail)
{
struct pios_usart_dev * usart_dev = (struct pios_usart_dev *)usart_id;
return usart_dev->cfg;
bool valid = PIOS_USART_validate(usart_dev);
PIOS_Assert(valid);
USART_ITConfig(usart_dev->cfg->regs, USART_IT_TXE, ENABLE);
}
/**
@ -240,170 +239,34 @@ static void PIOS_USART_ChangeBaud(uint32_t usart_id, uint32_t baud)
USART_Init(usart_dev->cfg->regs, &USART_InitStructure);
}
/**
* Returns number of used bytes in receive buffer
* \param[in] USART USART name
* \return > 0: number of used bytes
* \return 0 if USART not available
*/
static int32_t PIOS_USART_RxBufferUsed(uint32_t usart_id)
static void PIOS_USART_RegisterRxCallback(uint32_t usart_id, pios_com_callback rx_in_cb, uint32_t context)
{
struct pios_usart_dev * usart_dev = (struct pios_usart_dev *)usart_id;
bool valid = PIOS_USART_validate(usart_dev);
PIOS_Assert(valid)
PIOS_Assert(valid);
return (fifoBuf_getUsed(&usart_dev->rx));
/*
* Order is important in these assignments since ISR uses _cb
* field to determine if it's ok to dereference _cb and _context
*/
usart_dev->rx_in_context = context;
usart_dev->rx_in_cb = rx_in_cb;
}
/**
* Gets a byte from the receive buffer
* \param[in] USART USART name
* \return -1 if no new byte available
* \return >= 0: actual byte received
*/
static int32_t PIOS_USART_RxBufferGet(uint32_t usart_id)
static void PIOS_USART_RegisterTxCallback(uint32_t usart_id, pios_com_callback tx_out_cb, uint32_t context)
{
struct pios_usart_dev * usart_dev = (struct pios_usart_dev *)usart_id;
bool valid = PIOS_USART_validate(usart_dev);
PIOS_Assert(valid)
PIOS_Assert(valid);
if (fifoBuf_getUsed(&usart_dev->rx) == 0) {
/* Nothing new in the buffer */
return -1;
}
/* get byte - this operation should be atomic! */
uint8_t b = fifoBuf_getByte(&usart_dev->rx);
/* Return received byte */
return b;
}
/**
* puts a byte onto the receive buffer
* \param[in] USART USART name
* \param[in] b byte which should be put into Rx buffer
* \return 0 if no error
* \return -1 if buffer full (retry)
*/
static int32_t PIOS_USART_RxBufferPut(uint32_t usart_id, uint8_t b)
{
struct pios_usart_dev * usart_dev = (struct pios_usart_dev *)usart_id;
bool valid = PIOS_USART_validate(usart_dev);
PIOS_Assert(valid)
if (fifoBuf_getFree(&usart_dev->rx) < 1) {
/* Buffer full (retry) */
return -1;
}
/* Copy received byte into receive buffer */
/* This operation should be atomic! */
fifoBuf_putByte(&usart_dev->rx, b);
/* No error */
return 0;
}
/**
* returns number of used bytes in transmit buffer
* \param[in] USART USART name
* \return number of used bytes
* \return 0 if USART not available
*/
static int32_t PIOS_USART_TxBufferUsed(uint32_t usart_id)
{
struct pios_usart_dev * usart_dev = (struct pios_usart_dev *)usart_id;
bool valid = PIOS_USART_validate(usart_dev);
PIOS_Assert(valid)
return (fifoBuf_getUsed(&usart_dev->tx));
}
/**
* gets a byte from the transmit buffer
* \param[in] USART USART name
* \return -1 if no new byte available
* \return >= 0: transmitted byte
*/
static int32_t PIOS_USART_TxBufferGet(uint32_t usart_id)
{
struct pios_usart_dev * usart_dev = (struct pios_usart_dev *)usart_id;
bool valid = PIOS_USART_validate(usart_dev);
PIOS_Assert(valid)
if (fifoBuf_getUsed(&usart_dev->tx) == 0) {
/* Nothing new in the buffer */
return -1;
}
/* get byte - this operation should be atomic! */
PIOS_IRQ_Disable();
uint8_t b = fifoBuf_getByte(&usart_dev->tx);
PIOS_IRQ_Enable();
/* Return received byte */
return b;
}
/**
* puts more than one byte onto the transmit buffer (used for atomic sends)
* \param[in] USART USART name
* \param[in] *buffer pointer to buffer to be sent
* \param[in] len number of bytes to be sent
* \return 0 if no error
* \return -1 if buffer full or cannot get all requested bytes (retry)
*/
static int32_t PIOS_USART_TxBufferPutMoreNonBlocking(uint32_t usart_id, const uint8_t *buffer, uint16_t len)
{
struct pios_usart_dev * usart_dev = (struct pios_usart_dev *)usart_id;
bool valid = PIOS_USART_validate(usart_dev);
PIOS_Assert(valid)
if (len >= fifoBuf_getFree(&usart_dev->tx)) {
/* Buffer cannot accept all requested bytes (retry) */
return -1;
}
/* Copy bytes to be transmitted into transmit buffer */
/* This operation should be atomic! */
PIOS_IRQ_Disable();
uint16_t used = fifoBuf_getUsed(&usart_dev->tx);
fifoBuf_putData(&usart_dev->tx,buffer,len);
if (used == 0) {
/* enable sending when buffer was previously empty */
USART_ITConfig(usart_dev->cfg->regs, USART_IT_TXE, ENABLE);
}
PIOS_IRQ_Enable();
/* No error */
return 0;
}
/**
* puts more than one byte onto the transmit buffer (used for atomic sends)<BR>
* (blocking function)
* \param[in] USART USART name
* \param[in] *buffer pointer to buffer to be sent
* \param[in] len number of bytes to be sent
* \return 0 if no error
*/
static int32_t PIOS_USART_TxBufferPutMore(uint32_t usart_id, const uint8_t *buffer, uint16_t len)
{
int32_t rc;
while ((rc = PIOS_USART_TxBufferPutMoreNonBlocking(usart_id, buffer, len)) == -1);
return rc;
/*
* Order is important in these assignments since ISR uses _cb
* field to determine if it's ok to dereference _cb and _context
*/
usart_dev->tx_out_context = context;
usart_dev->tx_out_cb = tx_out_cb;
}
static void PIOS_USART_generic_irq_handler(uint32_t usart_id)
@ -413,41 +276,46 @@ static void PIOS_USART_generic_irq_handler(uint32_t usart_id)
bool valid = PIOS_USART_validate(usart_dev);
PIOS_Assert(valid);
/* Call any user provided callback function instead of processing
* the interrupt ourselves.
*/
if (usart_dev->cfg->irq.handler) {
(usart_dev->cfg->irq.handler)(usart_id);
return;
}
/* Force read of dr after sr to make sure to clear error flags */
volatile uint16_t sr = usart_dev->cfg->regs->SR;
volatile uint8_t dr = usart_dev->cfg->regs->DR;
/* Check if RXNE flag is set */
bool rx_need_yield = false;
if (sr & USART_SR_RXNE) {
if (PIOS_USART_RxBufferPut(usart_id, dr) < 0) {
/* Here we could add some error handling */
uint8_t byte = dr;
if (usart_dev->rx_in_cb) {
(void) (usart_dev->rx_in_cb)(usart_dev->rx_in_context, &byte, 1, NULL, &rx_need_yield);
}
}
/* Check if TXE flag is set */
bool tx_need_yield = false;
if (sr & USART_SR_TXE) {
if (PIOS_USART_TxBufferUsed(usart_id) > 0) {
int32_t b = PIOS_USART_TxBufferGet(usart_id);
if (usart_dev->tx_out_cb) {
uint8_t b;
uint16_t bytes_to_send;
if (b < 0) {
/* Here we could add some error handling */
usart_dev->cfg->regs->DR = 0xff;
bytes_to_send = (usart_dev->tx_out_cb)(usart_dev->tx_out_context, &b, 1, NULL, &tx_need_yield);
if (bytes_to_send > 0) {
/* Send the byte we've been given */
usart_dev->cfg->regs->DR = b;
} else {
usart_dev->cfg->regs->DR = b & 0xff;
/* No bytes to send, disable TXE interrupt */
USART_ITConfig(usart_dev->cfg->regs, USART_IT_TXE, DISABLE);
}
} else {
/* Disable TXE interrupt (TXEIE=0) */
/* No bytes to send, disable TXE interrupt */
USART_ITConfig(usart_dev->cfg->regs, USART_IT_TXE, DISABLE);
}
}
#if defined(PIOS_INCLUDE_FREERTOS)
if (rx_need_yield || tx_need_yield) {
vPortYieldFromISR();
}
#endif /* PIOS_INCLUDE_FREERTOS */
}
#endif

View File

@ -36,76 +36,106 @@
#include "usb_lib.h"
#include "pios_usb_hid_desc.h"
#include "stm32f10x.h"
#include "fifo_buffer.h"
#include "pios_usb_hid_priv.h"
#if defined(PIOS_INCLUDE_USB_HID)
#if defined(PIOS_INCLUDE_FREERTOS)
#define USE_FREERTOS
#endif
static int32_t PIOS_USB_HID_TxBufferPutMoreNonBlocking(uint32_t usbcom_id, const uint8_t *buffer, uint16_t len);
static int32_t PIOS_USB_HID_TxBufferPutMore(uint32_t usbcom_id, const uint8_t *buffer, uint16_t len);
static int32_t PIOS_USB_HID_RxBufferGet(uint32_t usbcom_id);
static int32_t PIOS_USB_HID_RxBufferUsed(uint32_t usbcom_id);
static void PIOS_USB_HID_TxStart(uint32_t usbcom_id, uint16_t tx_bytes_avail);
static void PIOS_USB_HID_RxStart(uint32_t usbcom_id, uint16_t rx_bytes_avail);
static void PIOS_USB_HID_RegisterTxCallback(uint32_t usbcom_id, pios_com_callback tx_out_cb, uint32_t context);
static void PIOS_USB_HID_RegisterRxCallback(uint32_t usbcom_id, pios_com_callback rx_in_cb, uint32_t context);
const struct pios_com_driver pios_usb_com_driver = {
.tx_nb = PIOS_USB_HID_TxBufferPutMoreNonBlocking,
.tx = PIOS_USB_HID_TxBufferPutMore,
.rx = PIOS_USB_HID_RxBufferGet,
.rx_avail = PIOS_USB_HID_RxBufferUsed,
.tx_start = PIOS_USB_HID_TxStart,
.rx_start = PIOS_USB_HID_RxStart,
.bind_tx_cb = PIOS_USB_HID_RegisterTxCallback,
.bind_rx_cb = PIOS_USB_HID_RegisterRxCallback,
};
// TODO: Eventually replace the transmit and receive buffers with bigger ring bufers
// so there isn't hte 64 byte cap in place by the USB interrupt packet definition
enum pios_usb_hid_dev_magic {
PIOS_USB_HID_DEV_MAGIC = 0xAABBCCDD,
};
struct pios_usb_hid_dev {
enum pios_usb_hid_dev_magic magic;
const struct pios_usb_hid_cfg * cfg;
pios_com_callback rx_in_cb;
uint32_t rx_in_context;
pios_com_callback tx_out_cb;
uint32_t tx_out_context;
uint8_t rx_packet_buffer[PIOS_USB_HID_DATA_LENGTH + 2];
uint8_t tx_packet_buffer[PIOS_USB_HID_DATA_LENGTH + 2];
};
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
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));
if (!usb_hid_dev) return(NULL);
usb_hid_dev->magic = PIOS_USB_HID_DEV_MAGIC;
return(usb_hid_dev);
}
#else
static struct pios_usb_hid_dev pios_usb_hid_devs[PIOS_USB_HID_MAX_DEVS];
static uint8_t pios_usb_hid_num_devs;
static struct pios_usb_hid_dev * PIOS_USB_HID_alloc(void)
{
struct pios_usb_hid_dev * usb_hid_dev;
if (pios_usb_hid_num_devs >= PIOS_USB_HID_MAX_DEVS) {
return (NULL);
}
usb_hid_dev = &pios_usb_hid_devs[pios_usb_hid_num_devs++];
usb_hid_dev->magic = PIOS_USB_HID_DEV_MAGIC;
return (usb_hid_dev);
}
#endif
/* Rx/Tx status */
static uint8_t transfer_possible = 0;
static uint8_t rx_packet_buffer[PIOS_USB_HID_DATA_LENGTH + 2] = { 0 };
static uint8_t tx_packet_buffer[PIOS_USB_HID_DATA_LENGTH + 2] = { 0 };
uint8_t rx_pios_fifo_buf[PIOS_USB_RX_BUFFER_SIZE] __attribute__ ((aligned(4))); // align to 32-bit to try and provide speed improvement
t_fifo_buffer rx_pios_fifo_buffer;
uint8_t tx_pios_fifo_buf[PIOS_USB_TX_BUFFER_SIZE] __attribute__ ((aligned(4))); // align to 32-bit to try and provide speed improvement
t_fifo_buffer tx_pios_fifo_buffer;
#if defined(USE_FREERTOS)
xSemaphoreHandle pios_usb_tx_semaphore;
#endif
/**
* Initialises USB COM layer
* \param[in] mode currently only mode 0 supported
* \return < 0 if initialisation failed
* \note Applications shouldn't call this function directly, instead please use \ref PIOS_COM layer functions
*/
int32_t PIOS_USB_HID_Init(uint32_t mode)
static uint32_t pios_usb_hid_id;
int32_t PIOS_USB_HID_Init(uint32_t * usb_hid_id, const struct pios_usb_hid_cfg * cfg)
{
/* Currently only mode 0 supported */
if (mode != 0) {
/* Unsupported mode */
return -1;
}
PIOS_Assert(usb_hid_id);
PIOS_Assert(cfg);
fifoBuf_init(&rx_pios_fifo_buffer, rx_pios_fifo_buf, sizeof(rx_pios_fifo_buf));
fifoBuf_init(&tx_pios_fifo_buffer, tx_pios_fifo_buf, sizeof(tx_pios_fifo_buf));
struct pios_usb_hid_dev * usb_hid_dev;
usb_hid_dev = (struct pios_usb_hid_dev *) PIOS_USB_HID_alloc();
if (!usb_hid_dev) goto out_fail;
/* Bind the configuration to the device instance */
usb_hid_dev->cfg = cfg;
PIOS_USB_HID_Reenumerate();
/* Create semaphore before enabling interrupts */
#if defined(USE_FREERTOS)
vSemaphoreCreateBinary(pios_usb_tx_semaphore);
#endif
/*
* This is a horrible hack to make this available to
* the interrupt callbacks. This should go away ASAP.
*/
pios_usb_hid_id = (uint32_t) usb_hid_dev;
/* Enable the USB Interrupts */
/* 2 bit for pre-emption priority, 2 bits for subpriority */
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_InitStructure.NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW;
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
NVIC_Init(&usb_hid_dev->cfg->irq.init);
/* Select USBCLK source */
RCC_USBCLKConfig(RCC_USBCLKSource_PLLCLK_1Div5);
@ -122,7 +152,12 @@ int32_t PIOS_USB_HID_Init(uint32_t mode)
USB_Init();
USB_SIL_Init();
*usb_hid_id = (uint32_t) usb_hid_dev;
return 0; /* No error */
out_fail:
return(-1);
}
/**
@ -201,127 +236,118 @@ int32_t PIOS_USB_HID_CheckAvailable(uint8_t id)
return (PIOS_USB_DETECT_GPIO_PORT->IDR & PIOS_USB_DETECT_GPIO_PIN) != 0 && transfer_possible ? 1 : 0;
}
void sendChunk()
static void PIOS_USB_HID_SendReport(struct pios_usb_hid_dev * usb_hid_dev)
{
uint16_t bytes_to_tx;
uint32_t size = fifoBuf_getUsed(&tx_pios_fifo_buffer);
if ((size > 0) && (GetEPTxStatus(ENDP1) != EP_TX_VALID)) {
if (size > PIOS_USB_HID_DATA_LENGTH)
size = PIOS_USB_HID_DATA_LENGTH;
if (!usb_hid_dev->tx_out_cb) {
return;
}
bool need_yield = false;
#ifdef USB_HID
fifoBuf_getData(&tx_pios_fifo_buffer, &tx_packet_buffer[1], size + 1);
tx_packet_buffer[0] = 1; /* report ID */
bytes_to_tx = (usb_hid_dev->tx_out_cb)(usb_hid_dev->tx_out_context,
&usb_hid_dev->tx_packet_buffer[1],
sizeof(usb_hid_dev->tx_packet_buffer)-1,
NULL,
&need_yield);
#else
fifoBuf_getData(&tx_pios_fifo_buffer, &tx_packet_buffer[2], size);
tx_packet_buffer[0] = 1; /* report ID */
tx_packet_buffer[1] = size; /* valid data length */
bytes_to_tx = (usb_hid_dev->tx_out_cb)(usb_hid_dev->tx_out_context,
&usb_hid_dev->tx_packet_buffer[2],
sizeof(usb_hid_dev->tx_packet_buffer)-2,
NULL,
&need_yield);
#endif
UserToPMABufferCopy((uint8_t *) tx_packet_buffer, GetEPTxAddr(EP1_IN & 0x7F), size + 2);
SetEPTxCount((EP1_IN & 0x7F), PIOS_USB_HID_DATA_LENGTH + 2);
/* Send Buffer */
SetEPTxValid(ENDP1);
if (bytes_to_tx == 0) {
return;
}
}
/* Always set type as report ID */
usb_hid_dev->tx_packet_buffer[0] = 1;
/**
* Puts more than one byte onto the transmit buffer (used for atomic sends)
* \param[in] *buffer pointer to buffer which should be transmitted
* \param[in] len number of bytes which should be transmitted
* \return 0 if no error
* \return -1 if port unavailable (disconnected)
* \return -2 if too many bytes to be send
* \note Applications shouldn't call this function directly, instead please use \ref PIOS_COM layer functions
*/
static int32_t PIOS_USB_HID_TxBufferPutMoreNonBlocking(uint32_t usbcom_id, const uint8_t * buffer, uint16_t len)
{
uint16_t ret;
if(!transfer_possible)
return -1;
if (len > fifoBuf_getFree(&tx_pios_fifo_buffer)) {
sendChunk(); /* Try and send what's in the buffer though */
return -2; /* Cannot send all requested bytes */
}
/* don't check returned bytes because it should always succeed */
/* after previous thread and no meaningful way to deal with the */
/* case it only buffers half the bytes */
#if defined(USE_FREERTOS)
if(!xSemaphoreTake(pios_usb_tx_semaphore,10 / portTICK_RATE_MS))
return -3;
#ifdef USB_HID
UserToPMABufferCopy(usb_hid_dev->tx_packet_buffer, GetEPTxAddr(EP1_IN & 0x7F), bytes_to_tx + 1);
#else
usb_hid_dev->tx_packet_buffer[1] = bytes_to_tx;
UserToPMABufferCopy(usb_hid_dev->tx_packet_buffer, GetEPTxAddr(EP1_IN & 0x7F), bytes_to_tx + 2);
#endif
/* Is this correct? Why do we always send the whole buffer? */
SetEPTxCount((EP1_IN & 0x7F), sizeof(usb_hid_dev->tx_packet_buffer));
SetEPTxValid(ENDP1);
ret = fifoBuf_putData(&tx_pios_fifo_buffer, buffer, len);
#if defined(USE_FREERTOS)
xSemaphoreGive(pios_usb_tx_semaphore);
#endif
sendChunk();
return 0;
}
/**
* Puts more than one byte onto the transmit buffer (used for atomic sends)<br>
* (Blocking Function)
* \param[in] *buffer pointer to buffer which should be transmitted
* \param[in] len number of bytes which should be transmitted
* \return 0 if no error
* \return -1 if too many bytes to be send
* \note Applications shouldn't call this function directly, instead please use \ref PIOS_COM layer functions
*/
static int32_t PIOS_USB_HID_TxBufferPutMore(uint32_t usbcom_id, const uint8_t *buffer, uint16_t len)
{
if(len > (fifoBuf_getUsed(&tx_pios_fifo_buffer) + fifoBuf_getFree(&tx_pios_fifo_buffer)))
return -1;
uint32_t error;
while ((error = PIOS_USB_HID_TxBufferPutMoreNonBlocking(usbcom_id, buffer, len)) == -2) {
#if defined(PIOS_INCLUDE_FREERTOS)
taskYIELD();
#endif
if (need_yield) {
vPortYieldFromISR();
}
return error;
#endif /* PIOS_INCLUDE_FREERTOS */
}
/**
* Gets a byte from the receive buffer
* \return -1 if no new byte available
* \return >= 0: received byte
* \note Applications shouldn't call this function directly, instead please use \ref PIOS_COM layer functions
*/
static int32_t PIOS_USB_HID_RxBufferGet(uint32_t usbcom_id)
{
uint8_t read;
static void PIOS_USB_HID_RxStart(uint32_t usbcom_id, uint16_t rx_bytes_avail) {
struct pios_usb_hid_dev * usb_hid_dev = (struct pios_usb_hid_dev *)usbcom_id;
if(fifoBuf_getUsed(&rx_pios_fifo_buffer) == 0)
return -1;
bool valid = PIOS_USB_HID_validate(usb_hid_dev);
PIOS_Assert(valid);
read = fifoBuf_getByte(&rx_pios_fifo_buffer);
if (!transfer_possible) {
return;
}
// If endpoint was stalled and there is now space make it valid
if ((GetEPRxStatus(ENDP1) != EP_RX_VALID) && (fifoBuf_getFree(&rx_pios_fifo_buffer) > 62)) {
PIOS_IRQ_Disable();
if ((GetEPRxStatus(ENDP1) != EP_RX_VALID) &&
(rx_bytes_avail > PIOS_USB_HID_DATA_LENGTH)) {
SetEPRxStatus(ENDP1, EP_RX_VALID);
}
return read;
PIOS_IRQ_Enable();
}
/**
* Returns number of used bytes in receive buffer
* \return > 0: number of used bytes
* \return 0 nothing available
* \note Applications shouldn't call these functions directly, instead please use \ref PIOS_COM layer functions
*/
static int32_t PIOS_USB_HID_RxBufferUsed(uint32_t usbcom_id)
static void PIOS_USB_HID_TxStart(uint32_t usbcom_id, uint16_t tx_bytes_avail)
{
return fifoBuf_getUsed(&rx_pios_fifo_buffer);
struct pios_usb_hid_dev * usb_hid_dev = (struct pios_usb_hid_dev *)usbcom_id;
bool valid = PIOS_USB_HID_validate(usb_hid_dev);
PIOS_Assert(valid);
if (!transfer_possible) {
return;
}
if (GetEPTxStatus(ENDP1) == EP_TX_VALID) {
/* Endpoint is already transmitting */
return;
}
PIOS_USB_HID_SendReport(usb_hid_dev);
}
static void PIOS_USB_HID_RegisterRxCallback(uint32_t usbcom_id, pios_com_callback rx_in_cb, uint32_t context)
{
struct pios_usb_hid_dev * usb_hid_dev = (struct pios_usb_hid_dev *)usbcom_id;
bool valid = PIOS_USB_HID_validate(usb_hid_dev);
PIOS_Assert(valid);
/*
* Order is important in these assignments since ISR uses _cb
* field to determine if it's ok to dereference _cb and _context
*/
usb_hid_dev->rx_in_context = context;
usb_hid_dev->rx_in_cb = rx_in_cb;
}
static void PIOS_USB_HID_RegisterTxCallback(uint32_t usbcom_id, pios_com_callback tx_out_cb, uint32_t context)
{
struct pios_usb_hid_dev * usb_hid_dev = (struct pios_usb_hid_dev *)usbcom_id;
bool valid = PIOS_USB_HID_validate(usb_hid_dev);
PIOS_Assert(valid);
/*
* Order is important in these assignments since ISR uses _cb
* field to determine if it's ok to dereference _cb and _context
*/
usb_hid_dev->tx_out_context = context;
usb_hid_dev->tx_out_cb = tx_out_cb;
}
/**
@ -330,7 +356,16 @@ static int32_t PIOS_USB_HID_RxBufferUsed(uint32_t usbcom_id)
*/
void PIOS_USB_HID_EP1_IN_Callback(void)
{
sendChunk();
struct pios_usb_hid_dev * usb_hid_dev = (struct pios_usb_hid_dev *)pios_usb_hid_id;
bool valid = PIOS_USB_HID_validate(usb_hid_dev);
PIOS_Assert(valid);
if (!transfer_possible) {
return;
}
PIOS_USB_HID_SendReport(usb_hid_dev);
}
/**
@ -338,28 +373,58 @@ void PIOS_USB_HID_EP1_IN_Callback(void)
*/
void PIOS_USB_HID_EP1_OUT_Callback(void)
{
struct pios_usb_hid_dev * usb_hid_dev = (struct pios_usb_hid_dev *)pios_usb_hid_id;
bool valid = PIOS_USB_HID_validate(usb_hid_dev);
PIOS_Assert(valid);
uint32_t DataLength = 0;
/* Read received data (63 bytes) */
/* Get the number of received data on the selected Endpoint */
DataLength = GetEPRxCount(ENDP1 & 0x7F);
if (DataLength > sizeof(usb_hid_dev->rx_packet_buffer)) {
DataLength = sizeof(usb_hid_dev->rx_packet_buffer);
}
/* Use the memory interface function to write to the selected endpoint */
PMAToUserBufferCopy((uint8_t *) &rx_packet_buffer[0], GetEPRxAddr(ENDP1 & 0x7F), DataLength);
PMAToUserBufferCopy((uint8_t *) usb_hid_dev->rx_packet_buffer, GetEPRxAddr(ENDP1 & 0x7F), DataLength);
if (!usb_hid_dev->rx_in_cb) {
/* No Rx call back registered, disable the receiver */
SetEPRxStatus(ENDP1, EP_RX_NAK);
return;
}
/* The first byte is report ID (not checked), the second byte is the valid data length */
uint16_t headroom;
bool need_yield = false;
#ifdef USB_HID
fifoBuf_putData(&rx_pios_fifo_buffer, &rx_packet_buffer[1], PIOS_USB_HID_DATA_LENGTH + 1);
(usb_hid_dev->rx_in_cb)(usb_hid_dev->rx_in_context,
&usb_hid_dev->rx_packet_buffer[1],
sizeof(usb_hid_dev->rx_packet_buffer)-1,
&headroom,
&need_yield);
#else
fifoBuf_putData(&rx_pios_fifo_buffer, &rx_packet_buffer[2], rx_packet_buffer[1]);
(usb_hid_dev->rx_in_cb)(usb_hid_dev->rx_in_context,
&usb_hid_dev->rx_packet_buffer[2],
usb_hid_dev->rx_packet_buffer[1],
&headroom,
&need_yield);
#endif
// Only reactivate endpoint if available space in buffer
if (fifoBuf_getFree(&rx_pios_fifo_buffer) > 62) {
if (headroom > PIOS_USB_HID_DATA_LENGTH) {
/* We have room for a maximum length message */
SetEPRxStatus(ENDP1, EP_RX_VALID);
} else {
/* Not enough room left for a message, apply backpressure */
SetEPRxStatus(ENDP1, EP_RX_NAK);
}
#if defined(PIOS_INCLUDE_FREERTOS)
if (need_yield) {
vPortYieldFromISR();
}
#endif /* PIOS_INCLUDE_FREERTOS */
}
#endif

View File

@ -32,17 +32,19 @@
#ifndef PIOS_COM_H
#define PIOS_COM_H
typedef uint16_t (*pios_com_callback)(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, bool * task_woken);
struct pios_com_driver {
void (*init)(uint32_t id);
void (*set_baud)(uint32_t id, uint32_t baud);
int32_t (*tx_nb)(uint32_t id, const uint8_t *buffer, uint16_t len);
int32_t (*tx)(uint32_t id, const uint8_t *buffer, uint16_t len);
int32_t (*rx)(uint32_t id);
int32_t (*rx_avail)(uint32_t id);
void (*init)(uint32_t id);
void (*set_baud)(uint32_t id, uint32_t baud);
void (*tx_start)(uint32_t id, uint16_t tx_bytes_avail);
void (*rx_start)(uint32_t id, uint16_t rx_bytes_avail);
void (*bind_rx_cb)(uint32_t id, pios_com_callback rx_in_cb, uint32_t context);
void (*bind_tx_cb)(uint32_t id, pios_com_callback tx_out_cb, uint32_t context);
};
/* Public Functions */
extern int32_t PIOS_COM_Init(uint32_t * com_id, const struct pios_com_driver * driver, const uint32_t lower_id);
extern int32_t PIOS_COM_Init(uint32_t * com_id, const struct pios_com_driver * driver, uint32_t lower_id, uint8_t * rx_buffer, uint16_t rx_buffer_len, uint8_t * tx_buffer, uint16_t tx_buffer_len);
extern int32_t PIOS_COM_ChangeBaud(uint32_t com_id, uint32_t baud);
extern int32_t PIOS_COM_SendCharNonBlocking(uint32_t com_id, char c);
extern int32_t PIOS_COM_SendChar(uint32_t com_id, char c);
@ -52,7 +54,7 @@ extern int32_t PIOS_COM_SendStringNonBlocking(uint32_t com_id, const char *str);
extern int32_t PIOS_COM_SendString(uint32_t com_id, const char *str);
extern int32_t PIOS_COM_SendFormattedStringNonBlocking(uint32_t com_id, const char *format, ...);
extern int32_t PIOS_COM_SendFormattedString(uint32_t com_id, const char *format, ...);
extern uint8_t PIOS_COM_ReceiveBuffer(uint32_t com_id);
extern uint16_t PIOS_COM_ReceiveBuffer(uint32_t com_id, uint8_t * buf, uint16_t buf_len, uint32_t timeout_ms);
extern int32_t PIOS_COM_ReceiveBufferUsed(uint32_t com_id);
#endif /* PIOS_COM_H */

View File

@ -34,16 +34,6 @@
#include <pios.h>
enum pios_com_dev_magic {
PIOS_COM_DEV_MAGIC = 0xaa55aa55,
};
struct pios_com_dev {
enum pios_com_dev_magic magic;
uint32_t id;
const struct pios_com_driver * driver;
};
extern int32_t PIOS_COM_ReceiveHandler(uint32_t com_id);
#endif /* PIOS_COM_PRIV_H */

View File

@ -34,10 +34,10 @@
/* Public Functions */
extern int32_t PIOS_DELAY_Init(void);
extern int32_t PIOS_DELAY_WaituS(uint16_t uS);
extern int32_t PIOS_DELAY_WaitmS(uint16_t mS);
extern uint16_t PIOS_DELAY_GetuS();
extern int32_t PIOS_DELAY_DiffuS(uint16_t ref);
extern int32_t PIOS_DELAY_WaituS(uint32_t uS);
extern int32_t PIOS_DELAY_WaitmS(uint32_t mS);
extern uint32_t PIOS_DELAY_GetuS();
extern uint32_t PIOS_DELAY_GetuSSince(uint32_t t);
#endif /* PIOS_DELAY_H */

View File

@ -39,8 +39,8 @@ struct pios_rcvr_channel_map {
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);
void (*init)(uint32_t id);
int32_t (*read)(uint32_t id, uint8_t channel);
};
/* Public Functions */

View File

@ -75,11 +75,9 @@ struct pios_sbus_cfg {
BitAction gpio_inv_enable;
};
extern void PIOS_SBUS_irq_handler();
extern const struct pios_rcvr_driver pios_sbus_rcvr_driver;
extern void PIOS_SBUS_Init(const struct pios_sbus_cfg * cfg);
extern int32_t PIOS_SBUS_Init(uint32_t * sbus_id, const struct pios_sbus_cfg *cfg, const struct pios_com_driver * driver, uint32_t lower_id);
#endif /* PIOS_SBUS_PRIV_H */

View File

@ -40,11 +40,9 @@ struct pios_spektrum_cfg {
uint32_t remap; /* GPIO_Remap_* */
};
extern void PIOS_SPEKTRUM_irq_handler();
extern const struct pios_rcvr_driver pios_spektrum_rcvr_driver;
extern void PIOS_SPEKTRUM_Init(const struct pios_spektrum_cfg * cfg, 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, bool bind);
#endif /* PIOS_PWM_PRIV_H */

View File

@ -32,7 +32,6 @@
#define PIOS_STM32_H
struct stm32_irq {
void (*handler) (uint32_t);
uint32_t flags;
NVIC_InitTypeDef init;
};

View File

@ -41,7 +41,6 @@
#define PIOS_USB_HID_DATA_LENGTH 62
/* Global functions */
extern int32_t PIOS_USB_HID_Init(uint32_t mode);
extern int32_t PIOS_USB_HID_Reenumerate();
extern int32_t PIOS_USB_HID_ChangeConnectionState(uint32_t Connected);
extern int32_t PIOS_USB_HID_CheckAvailable(uint8_t id);

View File

@ -0,0 +1,49 @@
/**
******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_USB_HID USB_HID Functions
* @brief PIOS interface for USB_HID port
* @{
*
* @file pios_usb_hid_priv.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief USB_HID private definitions.
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY
* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License
* for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PIOS_USB_HID_PRIV_H
#define PIOS_USB_HID_PRIV_H
#include <pios.h>
#include <pios_stm32.h>
struct pios_usb_hid_cfg {
struct stm32_irq irq;
};
extern int32_t PIOS_USB_HID_Init(uint32_t * usb_hid_id, const struct pios_usb_hid_cfg * cfg);
#endif /* PIOS_USB_HID_PRIV_H */
/**
* @}
* @}
*/

View File

@ -794,7 +794,8 @@ void apiconfig_process(void)
int32_t bytes = PIOS_COM_ReceiveBufferUsed(PIOS_COM_SERIAL);
while (bytes > 0)
{
PIOS_COM_ReceiveBuffer(PIOS_COM_SERIAL);
uint8_t c;
PIOS_COM_ReceiveBuffer(PIOS_COM_SERIAL, &c, 1, 0);
bytes--;
}
}
@ -812,9 +813,12 @@ void apiconfig_process(void)
if (com_num > sizeof(apiconfig_rx_buffer) - apiconfig_rx_buffer_wr)
com_num = sizeof(apiconfig_rx_buffer) - apiconfig_rx_buffer_wr;
while (com_num > 0)
{ // fetch a byte from the comm-port RX buffer and save it into our RX buffer
apiconfig_rx_buffer[apiconfig_rx_buffer_wr++] = PIOS_COM_ReceiveBuffer(apiconfig_comm_port);
uint8_t c;
PIOS_COM_ReceiveBuffer(apiconfig_comm_port, &c, 1, 0);
apiconfig_rx_buffer[apiconfig_rx_buffer_wr++] = c;
com_num--;
}

View File

@ -163,8 +163,8 @@ void TIMER_INT_FUNC(void)
// Clear timer interrupt pending bit
TIM_ClearITPendingBit(TIMER_INT_TIMER, TIM_IT_Update);
// random32 = UpdateCRC32(random32, PIOS_DELAY_TIMER->CNT >> 8);
// random32 = UpdateCRC32(random32, PIOS_DELAY_TIMER->CNT);
// random32 = UpdateCRC32(random32, PIOS_DELAY_GetuS() >> 8);
// random32 = UpdateCRC32(random32, PIOS_DELAY_GetuS());
uptime_ms++;
@ -785,8 +785,8 @@ int main()
for (;;)
{
random32 = updateCRC32(random32, PIOS_DELAY_TIMER->CNT >> 8);
random32 = updateCRC32(random32, PIOS_DELAY_TIMER->CNT);
random32 = updateCRC32(random32, PIOS_DELAY_GetuS() >> 8);
random32 = updateCRC32(random32, PIOS_DELAY_GetuS());
if (second_tick)
{

View File

@ -90,7 +90,6 @@ static const struct pios_spi_cfg pios_spi_port_cfg =
.ahb_clk = RCC_AHBPeriph_DMA1,
.irq =
{
.handler = NULL,
.flags = (DMA1_FLAG_TC2 | DMA1_FLAG_TE2 | DMA1_FLAG_HT2 | DMA1_FLAG_GL2),
.init = {
.NVIC_IRQChannel = DMA1_Channel2_IRQn,
@ -193,7 +192,6 @@ static const struct pios_adc_cfg pios_adc_cfg = {
.dma = {
.ahb_clk = RCC_AHBPeriph_DMA1,
.irq = {
.handler = NULL,
.flags = (DMA1_FLAG_TC1 | DMA1_FLAG_TE1 | DMA1_FLAG_HT1 | DMA1_FLAG_GL1),
.init = {
.NVIC_IRQChannel = DMA1_Channel1_IRQn,
@ -259,7 +257,6 @@ static const struct pios_usart_cfg pios_usart_serial_cfg =
},
.irq =
{
.handler = NULL,
.init =
{
.NVIC_IRQChannel = USART1_IRQn,
@ -298,10 +295,37 @@ static const struct pios_usart_cfg pios_usart_serial_cfg =
#include <pios_com_priv.h>
#define PIOS_COM_TELEM_USB_RX_BUF_LEN 192
#define PIOS_COM_TELEM_USB_TX_BUF_LEN 192
static uint8_t pios_com_telem_usb_rx_buffer[PIOS_COM_TELEM_USB_RX_BUF_LEN];
static uint8_t pios_com_telem_usb_tx_buffer[PIOS_COM_TELEM_USB_TX_BUF_LEN];
#define PIOS_COM_SERIAL_RX_BUF_LEN 192
#define PIOS_COM_SERIAL_TX_BUF_LEN 192
static uint8_t pios_com_serial_rx_buffer[PIOS_COM_SERIAL_RX_BUF_LEN];
static uint8_t pios_com_serial_tx_buffer[PIOS_COM_SERIAL_TX_BUF_LEN];
#endif /* PIOS_INCLUDE_COM */
// ***********************************************************************************
#if defined(PIOS_INCLUDE_USB_HID)
#include "pios_usb_hid_priv.h"
static const struct pios_usb_hid_cfg pios_usb_hid_main_cfg = {
.irq = {
.init = {
.NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn,
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW,
.NVIC_IRQChannelSubPriority = 0,
.NVIC_IRQChannelCmd = ENABLE,
},
},
};
#endif /* PIOS_INCLUDE_USB_HID */
extern const struct pios_com_driver pios_usb_com_driver;
uint32_t pios_com_serial_id;
@ -329,18 +353,23 @@ void PIOS_Board_Init(void) {
if (PIOS_USART_Init(&pios_usart_serial_id, &pios_usart_serial_cfg)) {
PIOS_DEBUG_Assert(0);
}
if (PIOS_COM_Init(&pios_com_serial_id, &pios_usart_com_driver, pios_usart_serial_id)) {
if (PIOS_COM_Init(&pios_com_serial_id, &pios_usart_com_driver, pios_usart_serial_id,
pios_com_serial_rx_buffer, sizeof(pios_com_serial_rx_buffer),
pios_com_serial_tx_buffer, sizeof(pios_com_serial_tx_buffer))) {
PIOS_DEBUG_Assert(0);
}
#if defined(PIOS_INCLUDE_USB_HID)
PIOS_USB_HID_Init(0);
uint32_t pios_usb_hid_id;
PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_main_cfg);
#if defined(PIOS_INCLUDE_COM)
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_com_driver, 0)) {
PIOS_DEBUG_Assert(0);
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_com_driver, pios_usb_hid_id,
pios_com_telem_usb_rx_buffer, sizeof(pios_com_telem_usb_rx_buffer),
pios_com_telem_usb_tx_buffer, sizeof(pios_com_telem_usb_tx_buffer))) {
PIOS_Assert(0);
}
#endif /* PIOS_INCLUDE_COM */
#endif /* PIOS_INCLUDE_USB_HID */
#endif /* PIOS_INCLUDE_USB_HID */
// ADC system
// PIOS_ADC_Init();

View File

@ -91,7 +91,8 @@ void trans_process(void)
int32_t bytes = PIOS_COM_ReceiveBufferUsed(PIOS_COM_SERIAL);
while (bytes > 0)
{
PIOS_COM_ReceiveBuffer(PIOS_COM_SERIAL);
uint8_t c;
PIOS_COM_ReceiveBuffer(PIOS_COM_SERIAL, &c, 1, 0);
bytes--;
}
}
@ -134,8 +135,7 @@ void trans_process(void)
// copy data received down the comm-port into our temp buffer
register uint16_t bytes_saved = 0;
while (bytes_saved < com_num)
trans_temp_buffer1[bytes_saved++] = PIOS_COM_ReceiveBuffer(comm_port);
bytes_saved = PIOS_COM_ReceiveBuffer(comm_port, trans_temp_buffer1, com_num, 0);
// put the received comm-port data bytes into the RF packet handler TX buffer
if (bytes_saved > 0)
@ -147,8 +147,11 @@ void trans_process(void)
else
{ // empty the comm-ports rx buffer
int32_t com_num = PIOS_COM_ReceiveBufferUsed(comm_port);
while (com_num > 0)
PIOS_COM_ReceiveBuffer(comm_port);
while (com_num > 0) {
uint8_t c;
PIOS_COM_ReceiveBuffer(comm_port, &c, 1, 0);
com_num--;
}
}
// ********************

View File

@ -1,7 +1,7 @@
define connect
target remote localhost:3333
monitor cortex_m3 vector_catch all
file ./build/bl_coptercontrol/CopterControl_BL.elf
file ./build/bl_coptercontrol/bl_coptercontrol.elf
end
#monitor reset halt

View File

@ -19,6 +19,19 @@ defineReplace(addNewline) {
return($$escape_expand(\\n\\t))
}
defineReplace(qtLibraryName) {
unset(LIBRARY_NAME)
LIBRARY_NAME = $$1
CONFIG(debug, debug|release) {
!debug_and_release|build_pass {
mac:RET = $$member(LIBRARY_NAME, 0)_debug
else:win32:RET = $$member(LIBRARY_NAME, 0)d
}
}
isEmpty(RET):RET = $$LIBRARY_NAME
return($$RET)
}
# For use in custom compilers which just copy files
win32:i_flag = i
defineReplace(stripSrcDir) {

View File

@ -11,16 +11,15 @@ SOURCES += main.cpp
include(../rpath.pri)
include(../libs/utils/utils.pri)
win32 {
CONFIG(debug, debug|release):LIBS *= -lExtensionSystemd -lAggregationd -lQExtSerialPortd
else:LIBS *= -lExtensionSystem -lAggregation -lQExtSerialPort
LIBS *= -l$$qtLibraryName(ExtensionSystem) -l$$qtLibraryName(Aggregation)
win32 {
# CONFIG(debug, debug|release):LIBS *= -lExtensionSystemd -lAggregationd -lQExtSerialPortd
# else:LIBS *= -lExtensionSystem -lAggregation -lQExtSerialPort
RC_FILE = openpilotgcs.rc
target.path = /bin
INSTALLS += target
} else:macx {
CONFIG(debug, debug|release):LIBS *= -lExtensionSystem_debug -lAggregation_debug
else:LIBS *= -lExtensionSystem -lAggregation
LIBS += -framework CoreFoundation
ICON = openpilotgcs.icns
QMAKE_INFO_PLIST = Info.plist
@ -28,8 +27,6 @@ win32 {
FILETYPES.path = Contents/Resources
QMAKE_BUNDLE_DATA += FILETYPES
} else {
LIBS *= -lExtensionSystem -lAggregation
target.path = /bin
INSTALLS += target
}

View File

@ -1 +1 @@
LIBS *= -l$$qtLibraryTarget(Aggregation)
LIBS *= -l$$qtLibraryName(Aggregation)

View File

@ -1,3 +1,3 @@
include(extensionsystem_dependencies.pri)
LIBS *= -l$$qtLibraryTarget(ExtensionSystem)
LIBS *= -l$$qtLibraryName(ExtensionSystem)

View File

@ -30,6 +30,11 @@
// Buffer offset used by VBO
#define BUFFER_OFFSET(i) ((char*)NULL + (i))
#if defined(Q_OS_MAC)
#include "gl.h"
#include "glu.h"
#endif
#if !defined(Q_OS_MAC)
// ARB_vertex_buffer_object
extern PFNGLBINDBUFFERARBPROC glBindBuffer;

View File

@ -1,2 +1,2 @@
QT += opengl
LIBS += -l$$qtLibraryTarget(GLC_lib)
LIBS *= -l$$qtLibraryName(GLC_lib)

View File

@ -25,6 +25,11 @@
#include "glc_camera.h"
#if defined(Q_OS_MAC)
#include "gl.h"
#include "glu.h"
#endif
#include <QtDebug>
using namespace glc;

View File

@ -1,4 +1,4 @@
LIBS += -l$$qtLibraryTarget(QxtCore)
LIBS *= -l$$qtLibraryName(QxtCore)
INCLUDEPATH += \
$$GCS_SOURCE_TREE/src/libs/libqxt/src/core

View File

@ -1 +1 @@
LIBS *= -l$$qtLibraryTarget(opmapwidget)
LIBS *= -l$$qtLibraryName(opmapwidget)

View File

@ -1,2 +1,2 @@
LIBS += -l$$qtLibraryTarget(QExtSerialPort)
LIBS *= -l$$qtLibraryName(QExtSerialPort)

View File

@ -135,6 +135,7 @@ struct PortSettings
#include <sys/select.h>
#include <QSocketNotifier>
#elif (defined Q_OS_WIN)
#include <QTimer>
#include <windows.h>
#include <QThread>
#include <QReadWriteLock>
@ -308,6 +309,9 @@ class QEXTSERIALPORT_EXPORT QextSerialPort: public QIODevice
#ifdef Q_OS_WIN
private slots:
void onWinEvent(HANDLE h);
void triggerTxEmpty();
private:
QTimer fakeTxEmpty;
#endif
private:

View File

@ -53,7 +53,6 @@ bool QextSerialPort::open(OpenMode mode) {
DWORD dwFlagsAndAttributes = 0;
if (queryMode() == QextSerialPort::EventDriven)
dwFlagsAndAttributes += FILE_FLAG_OVERLAPPED;
QMutexLocker lock(mutex);
if (mode == QIODevice::NotOpen)
return isOpen();
@ -95,7 +94,10 @@ bool QextSerialPort::open(OpenMode mode) {
}
winEventNotifier = new QWinEventNotifier(overlap.hEvent, this);
connect(winEventNotifier, SIGNAL(activated(HANDLE)), this, SLOT(onWinEvent(HANDLE)));
connect(&fakeTxEmpty,SIGNAL(timeout()),this,SLOT(triggerTxEmpty()));
fakeTxEmpty.start(10000);
WaitCommEvent(Win_Handle, &eventMask, &overlap);
}
}
} else {
@ -111,8 +113,10 @@ is not currently open.
void QextSerialPort::close()
{
QMutexLocker lock(mutex);
fakeTxEmpty.stop();
disconnect(&fakeTxEmpty,SIGNAL(timeout()),this,SLOT(triggerTxEmpty()));
if (isOpen()) {
flush();
flush();
QIODevice::close(); // mark ourselves as closed
CancelIo(Win_Handle);
if (CloseHandle(Win_Handle))
@ -886,4 +890,38 @@ void QextSerialPort::setTimeout(long millisec) {
if (queryMode() != QextSerialPort::EventDriven)
SetCommTimeouts(Win_Handle, &Win_CommTimeouts);
}
/*!
emulates the EV_TXEMPTY system event not present on some BT interfaces
*/
void QextSerialPort::triggerTxEmpty()
{
if (bytesToWrite()>500)
{
QMutexLocker lock(mutex);
qint64 totalBytesWritten = 0;
QList<OVERLAPPED*> overlapsToDelete;
foreach(OVERLAPPED* o, pendingWrites) {
DWORD numBytes = 0;
if (GetOverlappedResult(Win_Handle, o, & numBytes, false)) {
overlapsToDelete.append(o);
totalBytesWritten += numBytes;
} else if( GetLastError() != ERROR_IO_INCOMPLETE ) {
overlapsToDelete.append(o);
qWarning() << "CommEvent overlapped write error:" << GetLastError();
}
}
if (totalBytesWritten > 0) {
QWriteLocker writelocker(bytesToWriteLock);
_bytesToWrite = 0;
//qDebug()<<"zeroed bytesToWrite";
}
//qDebug()<<"overlapsToDelete"<<overlapsToDelete.count();
foreach(OVERLAPPED* o, overlapsToDelete) {
OVERLAPPED *toDelete = pendingWrites.takeAt(pendingWrites.indexOf(o));
CloseHandle(toDelete->hEvent);
delete toDelete;
}
}
}

View File

@ -1 +1 @@
LIBS *= -l$$qtLibraryTarget(QScienceSpinBox)
LIBS *= -l$$qtLibraryName(QScienceSpinBox)

View File

@ -1 +1 @@
LIBS *= -l$$qtLibraryTarget(QtConcurrent)
LIBS *= -l$$qtLibraryName(QtConcurrent)

View File

@ -1,2 +1,2 @@
LIBS += -l$$qtLibraryTarget(Qwt)
LIBS *= -l$$qtLibraryName(Qwt)

View File

@ -1 +1 @@
LIBS += -l$$qtLibraryTarget(sdlgamepad)
LIBS *= -l$$qtLibraryName(sdlgamepad)

View File

@ -0,0 +1,38 @@
/**
******************************************************************************
*
* @file mylistwidget.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup
* @{
*
*****************************************************************************/
/*
* 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 "mylistwidget.h"
QStyleOptionViewItem MyListWidget::viewOptions() const
{
QStyleOptionViewItem option = QListWidget::viewOptions();
if (m_iconAbove) {
option.decorationPosition = QStyleOptionViewItem::Top;
option.displayAlignment = Qt::AlignCenter;
}
return option;
}

View File

@ -0,0 +1,53 @@
/**
******************************************************************************
*
* @file mylistwidget.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup
* @{
*
*****************************************************************************/
/*
* 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 MYLISTWIDGET_H
#define MYLISTWIDGET_H
#include "utils_global.h"
#include <QtGui/QListWidget>
/*
* MyListWidget is a plain QListWidget but with the added option
* to place the icon above the label in ListMode. This is achieved
* the easiest by subclassing QListWidget and overriding viewOptions().
*/
class QTCREATOR_UTILS_EXPORT MyListWidget : public QListWidget
{
Q_OBJECT
public:
MyListWidget(QWidget *parent) : QListWidget(parent), m_iconAbove(false) { }
void setIconAbove(bool iconAbove) { m_iconAbove = iconAbove; }
protected:
QStyleOptionViewItem viewOptions() const;
private:
bool m_iconAbove;
};
#endif // MYLISTWIDGET_H

View File

@ -0,0 +1,109 @@
/**
******************************************************************************
*
* @file mytabbedstackwidget.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup
* @{
*
*****************************************************************************/
/*
* 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 "mytabbedstackwidget.h"
#include <QtGui/QVBoxLayout>
#include <QtGui/QHBoxLayout>
#include <QtGui/QLabel>
#include <QtCore/QDebug>
MyTabbedStackWidget::MyTabbedStackWidget(QWidget *parent, bool isVertical, bool iconAbove)
: QWidget(parent),
m_vertical(isVertical),
m_iconAbove(iconAbove)
{
m_listWidget = new MyListWidget(this);
m_listWidget->setIconAbove(m_iconAbove);
m_stackWidget = new QStackedWidget();
m_stackWidget->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
QBoxLayout *toplevelLayout;
if (m_vertical) {
toplevelLayout = new QHBoxLayout;
toplevelLayout->addWidget(m_listWidget);
toplevelLayout->addWidget(m_stackWidget);
m_listWidget->setFlow(QListView::TopToBottom);
m_listWidget->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Expanding);
} else {
toplevelLayout = new QVBoxLayout;
toplevelLayout->addWidget(m_stackWidget);
toplevelLayout->addWidget(m_listWidget);
m_listWidget->setFlow(QListView::LeftToRight);
m_listWidget->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Fixed);
}
if (m_iconAbove && m_vertical)
m_listWidget->setFixedWidth(90); // this should be computed instead
toplevelLayout->setSpacing(0);
toplevelLayout->setContentsMargins(0, 0, 0, 0);
m_listWidget->setSpacing(0);
m_listWidget->setContentsMargins(0, 0, 0, 0);
m_stackWidget->setContentsMargins(0, 0, 0, 0);
setLayout(toplevelLayout);
connect(m_listWidget, SIGNAL(currentRowChanged(int)), this, SLOT(showWidget(int)));
}
void MyTabbedStackWidget::insertTab(const int index, QWidget *tab, const QIcon &icon, const QString &label)
{
tab->setContentsMargins(0, 0, 0, 0);
m_stackWidget->insertWidget(index, tab);
QListWidgetItem *item = new QListWidgetItem(icon, label);
item->setToolTip(label);
m_listWidget->insertItem(index, item);
}
void MyTabbedStackWidget::removeTab(int index)
{
m_stackWidget->removeWidget(m_stackWidget->widget(index));
QListWidgetItem *item = m_listWidget->item(index);
m_listWidget->removeItemWidget(item);
delete item;
}
int MyTabbedStackWidget::currentIndex() const
{
return m_listWidget->currentRow();
}
void MyTabbedStackWidget::setCurrentIndex(int index)
{
m_listWidget->setCurrentRow(index);
}
void MyTabbedStackWidget::showWidget(int index)
{
emit currentAboutToShow(index);
m_stackWidget->setCurrentIndex(index);
emit currentChanged(index);
}
void MyTabbedStackWidget::insertCornerWidget(int index, QWidget *widget)
{
widget->hide();
}

View File

@ -0,0 +1,74 @@
/**
******************************************************************************
*
* @file mytabbedstackwidget.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup
* @{
*
*****************************************************************************/
/*
* 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 MYTABBEDSTACKWIDGET_H
#define MYTABBEDSTACKWIDGET_H
#include "utils/mylistwidget.h"
#include <QtGui/QStackedWidget>
/*
* MyTabbedStackWidget is a MyListWidget combined with a QStackedWidget,
* similar in function to QTabWidget.
*/
class QTCREATOR_UTILS_EXPORT MyTabbedStackWidget : public QWidget
{
Q_OBJECT
public:
MyTabbedStackWidget(QWidget *parent = 0, bool isVertical = false, bool iconAbove = true);
void insertTab(int index, QWidget *tab, const QIcon &icon, const QString &label);
void removeTab(int index);
void setIconSize(int size) { m_listWidget->setIconSize(QSize(size, size)); }
int currentIndex() const;
void insertCornerWidget(int index, QWidget *widget);
int cornerWidgetCount() { return m_cornerWidgetCount; }
signals:
void currentAboutToShow(int index);
void currentChanged(int index);
public slots:
void setCurrentIndex(int index);
private slots:
void showWidget(int index);
private:
MyListWidget *m_listWidget;
QStackedWidget *m_stackWidget;
QWidget *m_selectionWidget;
bool m_vertical;
bool m_iconAbove;
int m_cornerWidgetCount;
};
#endif // MYTABBEDSTACKWIDGET_H

View File

@ -0,0 +1,48 @@
/**
******************************************************************************
*
* @file mytabwidget.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup
* @{
*
*****************************************************************************/
/*
* 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 "mytabwidget.h"
#include <QtGui/QTabBar>
MyTabWidget::MyTabWidget(QWidget *parent)
: QTabWidget(parent)
{
QTabBar *tabBar = QTabWidget::tabBar();
connect(tabBar, SIGNAL(tabMoved(int, int)), this, SLOT(myTabMoved(int,int)));
}
void MyTabWidget::moveTab(int from, int to)
{
QTabBar *tabBar = QTabWidget::tabBar();
tabBar->moveTab(from, to);
}
void MyTabWidget::myTabMoved(int from, int to)
{
emit tabMoved(from, to);
}

View File

@ -0,0 +1,55 @@
/**
******************************************************************************
*
* @file mytabwidget.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* Parts by Nokia Corporation (qt-info@nokia.com) Copyright (C) 2009.
* @brief
* @see The GNU Public License (GPL) Version 3
* @defgroup
* @{
*
*****************************************************************************/
/*
* 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 MYTABWIDGET_H
#define MYTABWIDGET_H
#include "utils_global.h"
#include <QtGui/QTabWidget>
/*
* MyTabWidget is a plain QTabWidget with the addition of the signal
* tabMoved(int, int) which QTabBar has but for some reason is
* not made available from QTabWidget.
*/
class QTCREATOR_UTILS_EXPORT MyTabWidget : public QTabWidget
{
Q_OBJECT
public:
MyTabWidget(QWidget *parent = 0);
void moveTab(int from, int to);
private slots:
void myTabMoved(int from, int to);
signals:
void tabMoved(int from, int to);
};
#endif // MYTABWIDGET_H

View File

@ -1,9 +1 @@
macx {
CONFIG(debug, debug|release):LIBS *= -lUtils_debug
else:LIBS *= -lUtils
} else:win32 {
CONFIG(debug, debug|release):LIBS *= -lUtilsd
else:LIBS *= -lUtils
} else {
LIBS += -l$$qtLibraryTarget(Utils)
}
LIBS *= -l$$qtLibraryName(Utils)

View File

@ -45,7 +45,10 @@ SOURCES += reloadpromptutils.cpp \
coordinateconversions.cpp \
pathutils.cpp \
worldmagmodel.cpp \
homelocationutil.cpp
homelocationutil.cpp \
mytabbedstackwidget.cpp \
mytabwidget.cpp \
mylistwidget.cpp
SOURCES += xmlconfig.cpp
win32 {
@ -96,7 +99,10 @@ HEADERS += utils_global.h \
coordinateconversions.h \
pathutils.h \
worldmagmodel.h \
homelocationutil.h
homelocationutil.h \
mytabbedstackwidget.h \
mytabwidget.h \
mylistwidget.h
HEADERS += xmlconfig.h
FORMS += filewizardpage.ui \

View File

@ -8,7 +8,7 @@ DESTDIR = $$GCS_LIBRARY_PATH
include(rpath.pri)
TARGET = $$qtLibraryTarget($$TARGET)
TARGET = $$qtLibraryName($$TARGET)
contains(QT_CONFIG, reduce_exports):CONFIG += hGCS_symbols

View File

@ -23,7 +23,7 @@ copy2build.name = COPY ${QMAKE_FILE_IN}
copy2build.CONFIG += no_link
QMAKE_EXTRA_COMPILERS += copy2build
TARGET = $$qtLibraryTarget($$TARGET)
TARGET = $$qtLibraryName($$TARGET)
macx {
QMAKE_LFLAGS_SONAME = -Wl,-install_name,@executable_path/../Plugins/$${PROVIDER}/

View File

@ -23,7 +23,7 @@
<attribute name="title">
<string>Mixer Settings</string>
</attribute>
<layout class="QVBoxLayout" name="verticalLayout_2" stretch="0,0,0,0">
<layout class="QVBoxLayout" name="verticalLayout_2" stretch="0,0,0">
<property name="margin">
<number>5</number>
</property>
@ -1138,7 +1138,7 @@ Typical value is 50% for + or X configuration on quads.</string>
<item>
<widget class="QGroupBox" name="groupBox_4">
<property name="title">
<string>Throtle Curve 1</string>
<string>Curve 1</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_7">
<item>
@ -1208,7 +1208,7 @@ Typical value is 50% for + or X configuration on quads.</string>
<item>
<widget class="QGroupBox" name="groupBox_5">
<property name="title">
<string>Throtle Curve 2</string>
<string>Curve 2</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_17">
<item>
@ -1731,75 +1731,6 @@ Typical value is 50% for + or X configuration on quads.</string>
</widget>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_2">
<item>
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="airframeHelp">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="text">
<string/>
</property>
<property name="icon">
<iconset resource="../coreplugin/core.qrc">
<normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset>
</property>
<property name="iconSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="flat">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="saveAircraftToRAM">
<property name="toolTip">
<string>Send to board, but don't save permanently (flash or SD).</string>
</property>
<property name="text">
<string>Apply</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="saveAircraftToSD">
<property name="toolTip">
<string>Applies and Saves all settings to flash or SD depending on board.</string>
</property>
<property name="text">
<string>Save</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
<widget class="QWidget" name="tab">
@ -1808,7 +1739,7 @@ Typical value is 50% for + or X configuration on quads.</string>
</attribute>
<layout class="QVBoxLayout" name="verticalLayout_25">
<item>
<layout class="QVBoxLayout" name="verticalLayout_11" stretch="0,1,0,0,0,0">
<layout class="QVBoxLayout" name="verticalLayout_11" stretch="0,1,0,0,0">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_24">
<item>
@ -2082,14 +2013,14 @@ p, li { white-space: pre-wrap; }
<string>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:'Lucida Grande'; font-size:13pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;table border=&quot;0&quot; style=&quot;-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;&quot;&gt;
&lt;tr&gt;
&lt;td style=&quot;border: none;&quot;&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Ubuntu'; font-size:14pt; font-weight:600; color:#ff0000;&quot;&gt;SETTING UP FEED FORWARD IS DANGEROUS&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;&quot;&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;Beware: Feed Forward Tuning will launch all engines around mid-throttle, you have been warned!&lt;/p&gt;
&lt;p style=&quot; margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;Remove your props initially, and for fine-tuning, make sure your airframe is safely held in place. Wear glasses and protect your face and body.&lt;/p&gt;&lt;/td&gt;&lt;/tr&gt;&lt;/table&gt;&lt;/body&gt;&lt;/html&gt;</string>
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Lucida Grande'; font-size:13pt;&quot;&gt;Beware: Feed Forward Tuning will launch all engines around mid-throttle, you have been warned!&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-family:'Lucida Grande'; font-size:13pt;&quot;&gt;Remove your props initially, and for fine-tuning, make sure your airframe is safely held in place. Wear glasses and protect your face and body.&lt;/span&gt;&lt;/p&gt;&lt;/td&gt;&lt;/tr&gt;&lt;/table&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
</widget>
</item>
@ -2106,49 +2037,81 @@ p, li { white-space: pre-wrap; }
</property>
</spacer>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_21">
<item>
<spacer name="horizontalSpacer_14">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="ffApply">
<property name="toolTip">
<string>Send to board, but don't save permanently (flash or SD).</string>
</property>
<property name="text">
<string>Apply</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="ffSave">
<property name="toolTip">
<string>Applies and Saves all settings to flash or SD depending on board.</string>
</property>
<property name="text">
<string>Save</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_2">
<item>
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="airframeHelp">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="text">
<string/>
</property>
<property name="icon">
<iconset resource="../coreplugin/core.qrc">
<normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset>
</property>
<property name="iconSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="flat">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="saveAircraftToRAM">
<property name="toolTip">
<string>Send to board, but don't save permanently (flash or SD).</string>
</property>
<property name="text">
<string>Apply</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="saveAircraftToSD">
<property name="toolTip">
<string>Applies and Saves all settings to flash or SD depending on board.</string>
</property>
<property name="text">
<string>Save</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
<customwidgets>

View File

@ -0,0 +1,283 @@
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>CC_HW_Widget</class>
<widget class="QWidget" name="CC_HW_Widget">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>517</width>
<height>487</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<widget class="QFrame" name="frame">
<property name="frameShape">
<enum>QFrame::StyledPanel</enum>
</property>
<property name="frameShadow">
<enum>QFrame::Raised</enum>
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">
<item>
<layout class="QGridLayout" name="gridLayout">
<item row="1" column="1" rowspan="5" colspan="3">
<widget class="QLabel" name="label_2">
<property name="text">
<string/>
</property>
<property name="pixmap">
<pixmap resource="configgadget.qrc">:/configgadget/images/coptercontrol.svg</pixmap>
</property>
<property name="scaledContents">
<bool>true</bool>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QComboBox" name="cbFlexi"/>
</item>
<item row="4" column="0">
<widget class="QComboBox" name="cbTele"/>
</item>
<item row="3" column="0">
<widget class="QLabel" name="label_3">
<property name="text">
<string>MainPort</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft</set>
</property>
</widget>
</item>
<item row="5" column="0">
<widget class="QLabel" name="label_4">
<property name="text">
<string/>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_5">
<property name="text">
<string>FlexiPort</string>
</property>
<property name="alignment">
<set>Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft</set>
</property>
</widget>
</item>
<item row="1" column="4">
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="1">
<widget class="QLabel" name="label_7">
<property name="text">
<string>Receiver type</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QComboBox" name="receiverType"/>
</item>
</layout>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<widget class="QLabel" name="label">
<property name="text">
<string>Telemetry speed:</string>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="telemetrySpeed">
<property name="toolTip">
<string>Select the speed here.</string>
</property>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_3">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<widget class="QLabel" name="problems">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string/>
</property>
<property name="textFormat">
<enum>Qt::AutoText</enum>
</property>
<property name="wordWrap">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QLabel" name="label_6">
<property name="font">
<font>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Changes on this page only take effect after board reset or power cycle</string>
</property>
<property name="wordWrap">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout_2">
<item>
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QPushButton" name="cchwHelp">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="text">
<string/>
</property>
<property name="icon">
<iconset resource="../coreplugin/core.qrc">
<normaloff>:/core/images/helpicon.svg</normaloff>:/core/images/helpicon.svg</iconset>
</property>
<property name="iconSize">
<size>
<width>32</width>
<height>32</height>
</size>
</property>
<property name="flat">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="saveTelemetryToRAM">
<property name="toolTip">
<string>Send to OpenPilot but don't write in SD.
Beware of not locking yourself out!</string>
</property>
<property name="autoFillBackground">
<bool>true</bool>
</property>
<property name="styleSheet">
<string notr="true"/>
</property>
<property name="text">
<string>Apply</string>
</property>
<property name="checkable">
<bool>false</bool>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="saveTelemetryToSD">
<property name="toolTip">
<string>Applies and Saves all settings to SD.
Beware of not locking yourself out!</string>
</property>
<property name="autoFillBackground">
<bool>false</bool>
</property>
<property name="styleSheet">
<string notr="true"/>
</property>
<property name="text">
<string>Save</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
</item>
</layout>
</widget>
<resources>
<include location="configgadget.qrc"/>
<include location="../coreplugin/core.qrc"/>
</resources>
<connections/>
</ui>

View File

@ -24,7 +24,8 @@ HEADERS += configplugin.h \
configoutputwidget.h \
configtaskwidget.h \
configairframewidget.h \
configtelemetrywidget.h \
config_pro_hw_widget.h \
config_cc_hw_widget.h \
configahrswidget.h \
configccattitudewidget.h \
mixercurvewidget.h \
@ -34,7 +35,9 @@ HEADERS += configplugin.h \
configstabilizationwidget.h \
assertions.h \
calibration.h \
defaultattitudewidget.h
defaultattitudewidget.h \
smartsavebutton.h \
defaulthwsettingswidget.h
SOURCES += configplugin.cpp \
configgadgetconfiguration.cpp \
@ -47,7 +50,8 @@ SOURCES += configplugin.cpp \
configinputwidget.cpp \
configoutputwidget.cpp \
configairframewidget.cpp \
configtelemetrywidget.cpp \
config_pro_hw_widget.cpp \
config_cc_hw_widget.cpp \
configahrswidget.cpp \
configccattitudewidget.cpp \
mixercurvewidget.cpp \
@ -59,17 +63,21 @@ SOURCES += configplugin.cpp \
legacy-calibration.cpp \
gyro-calibration.cpp \
alignment-calibration.cpp \
defaultattitudewidget.cpp
defaultattitudewidget.cpp \
smartsavebutton.cpp \
defaulthwsettingswidget.cpp
FORMS += \
airframe.ui \
telemetry.ui \
cc_hw_settings.ui \
pro_hw_settings.ui \
ahrs.ui \
ccpm.ui \
stabilization.ui \
input.ui \
output.ui \
ccattitude.ui \
defaultattitude.ui
defaultattitude.ui \
defaulthwsettings.ui
RESOURCES += configgadget.qrc

View File

@ -0,0 +1,102 @@
/**
******************************************************************************
*
* @file configtelemetrywidget.h
* @author E. Lafargue & The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup ConfigPlugin Config Plugin
* @{
* @brief The Configuration Gadget used to update settings in the firmware
*****************************************************************************/
/*
* 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 "config_cc_hw_widget.h"
#include <QDebug>
#include <QStringList>
#include <QtGui/QWidget>
#include <QtGui/QTextEdit>
#include <QtGui/QVBoxLayout>
#include <QtGui/QPushButton>
#include <QDesktopServices>
#include <QUrl>
ConfigCCHWWidget::ConfigCCHWWidget(QWidget *parent) : ConfigTaskWidget(parent)
{
m_telemetry = new Ui_CC_HW_Widget();
m_telemetry->setupUi(this);
setupButtons(m_telemetry->saveTelemetryToRAM,m_telemetry->saveTelemetryToSD);
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);
connect(m_telemetry->cchwHelp,SIGNAL(clicked()),this,SLOT(openHelp()));
enableControls(false);
populateWidgets();
refreshWidgetsValues();
}
ConfigCCHWWidget::~ConfigCCHWWidget()
{
// Do nothing
}
void ConfigCCHWWidget::refreshValues()
{
}
void ConfigCCHWWidget::widgetsContentsChanged()
{
ConfigTaskWidget::widgetsContentsChanged();
enableControls(false);
if((m_telemetry->cbFlexi->currentText()==m_telemetry->cbTele->currentText()) && m_telemetry->cbTele->currentText()!="Disabled")
{
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("");
enableControls(true);
}
}
void ConfigCCHWWidget::openHelp()
{
QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/CopterControl+HW+Settings", QUrl::StrictMode) );
}
/**
* @}
* @}
*/

View File

@ -0,0 +1,55 @@
/**
******************************************************************************
*
* @file configtelemetrytwidget.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup ConfigPlugin Config Plugin
* @{
* @brief Telemetry configuration panel
*****************************************************************************/
/*
* 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 CONFIGCCHWWIDGET_H
#define CONFIGCCHWWIDGET_H
#include "ui_cc_hw_settings.h"
#include "configtaskwidget.h"
#include "extensionsystem/pluginmanager.h"
#include "uavobjectmanager.h"
#include "uavobject.h"
#include <QtGui/QWidget>
#include <QList>
#include "smartsavebutton.h"
class ConfigCCHWWidget: public ConfigTaskWidget
{
Q_OBJECT
public:
ConfigCCHWWidget(QWidget *parent = 0);
~ConfigCCHWWidget();
private slots:
void openHelp();
void refreshValues();
void widgetsContentsChanged();
private:
Ui_CC_HW_Widget *m_telemetry;
};
#endif // CONFIGCCHWWIDGET_H

View File

@ -0,0 +1,60 @@
/**
******************************************************************************
*
* @file configtelemetrywidget.h
* @author E. Lafargue & The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup ConfigPlugin Config Plugin
* @{
* @brief The Configuration Gadget used to update settings in the firmware
*****************************************************************************/
/*
* 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 "config_pro_hw_widget.h"
#include <QDebug>
#include <QStringList>
#include <QtGui/QWidget>
#include <QtGui/QTextEdit>
#include <QtGui/QVBoxLayout>
#include <QtGui/QPushButton>
ConfigProHWWidget::ConfigProHWWidget(QWidget *parent) : ConfigTaskWidget(parent)
{
m_telemetry = new Ui_PRO_HW_Widget();
m_telemetry->setupUi(this);
setupButtons(m_telemetry->saveTelemetryToRAM,m_telemetry->saveTelemetryToSD);
addUAVObjectToWidgetRelation("TelemetrySettings","Speed",m_telemetry->telemetrySpeed);
enableControls(false);
populateWidgets();
refreshWidgetsValues();
}
ConfigProHWWidget::~ConfigProHWWidget()
{
// Do nothing
}
/**
Request telemetry settings from the board
*/
void ConfigProHWWidget::refreshValues()
{
}

View File

@ -24,10 +24,10 @@
* with this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef CONFIGTELEMETRYWIDGET_H
#define CONFIGTELEMETRYWIDGET_H
#ifndef CONFIGPROHWWIDGET_H
#define CONFIGPROHWWIDGET_H
#include "ui_telemetry.h"
#include "ui_pro_hw_settings.h"
#include "configtaskwidget.h"
#include "extensionsystem/pluginmanager.h"
#include "uavobjectmanager.h"
@ -36,23 +36,20 @@
#include <QList>
class ConfigTelemetryWidget: public ConfigTaskWidget
class ConfigProHWWidget: public ConfigTaskWidget
{
Q_OBJECT
public:
ConfigTelemetryWidget(QWidget *parent = 0);
~ConfigTelemetryWidget();
ConfigProHWWidget(QWidget *parent = 0);
~ConfigProHWWidget();
private:
Ui_TelemetryWidget *m_telemetry;
void enableControls(bool enable);
Ui_PRO_HW_Widget *m_telemetry;
private slots:
virtual void refreshValues();
void sendTelemetryUpdate();
void saveTelemetryUpdate();
};
#endif // ConfigTelemetryWidget_H
#endif // CONFIGPROHWWIDGET_H

View File

@ -91,6 +91,32 @@ ConfigAirframeWidget::ConfigAirframeWidget(QWidget *parent) : ConfigTaskWidget(p
m_aircraft = new Ui_AircraftWidget();
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");
ffTuningInProgress = false;
ffTuningPhase = false;
@ -164,11 +190,6 @@ ConfigAirframeWidget::ConfigAirframeWidget(QWidget *parent) : ConfigTaskWidget(p
m_aircraft->customMixerTable->setItemDelegateForRow(i, sbd);
}
connect(m_aircraft->saveAircraftToSD, SIGNAL(clicked()), this, SLOT(saveAircraftUpdate()));
connect(m_aircraft->saveAircraftToRAM, SIGNAL(clicked()), this, SLOT(sendAircraftUpdate()));
connect(m_aircraft->ffSave, SIGNAL(clicked()), this, SLOT(saveAircraftUpdate()));
connect(m_aircraft->ffApply, SIGNAL(clicked()), this, SLOT(sendAircraftUpdate()));
connect(m_aircraft->fixedWingType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupAirframeUI(QString)));
connect(m_aircraft->multirotorFrameType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupAirframeUI(QString)));
connect(m_aircraft->aircraftType, SIGNAL(currentIndexChanged(int)), this, SLOT(switchAirframeType(int)));
@ -191,17 +212,8 @@ ConfigAirframeWidget::ConfigAirframeWidget(QWidget *parent) : ConfigTaskWidget(p
connect(m_aircraft->ffTestBox3, SIGNAL(clicked(bool)), this, SLOT(enableFFTest()));
enableControls(false);
refreshValues();
connect(parent, SIGNAL(autopilotConnected()),this, SLOT(onAutopilotConnect()));
connect(parent, SIGNAL(autopilotDisconnected()), this, SLOT(onAutopilotDisconnect()));
refreshWidgetsValues();
// Register for ManualControlSettings changes:
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("SystemSettings")));
connect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(refreshValues()));
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
connect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(refreshValues()));
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("ActuatorSettings")));
connect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(refreshValues()));
// Connect the help button
connect(m_aircraft->airframeHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
@ -213,18 +225,6 @@ ConfigAirframeWidget::~ConfigAirframeWidget()
// Do nothing
}
/**
Enable or disable controls depending on whether we're ronnected or not
*/
void ConfigAirframeWidget::enableControls(bool enable)
{
//m_aircraft->saveAircraftToRAM->setEnabled(enable);
m_aircraft->saveAircraftToSD->setEnabled(enable);
//m_aircraft->ffApply->setEnabled(enable);
m_aircraft->ffSave->setEnabled(enable);
}
/**
Slot for switching the airframe type. We do it explicitely
rather than a signal in the UI, because we want to force a fitInView of the quad shapes.
@ -460,7 +460,7 @@ void ConfigAirframeWidget::updateCustomThrottle2CurveValue(QList<double> list, d
/**
Refreshes the current value of the SystemSettings which holds the aircraft type
*/
void ConfigAirframeWidget::refreshValues()
void ConfigAirframeWidget::refreshWidgetsValues()
{
// Get the Airframe type from the system settings:
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("SystemSettings")));
@ -665,10 +665,13 @@ void ConfigAirframeWidget::refreshValues()
val = floor(-field->getDouble(i)/1.27);
m_aircraft->mrYawMixLevel->setValue(val);
eng = m_aircraft->multiMotor2->currentIndex()-1;
field = obj->getField(mixerVectors.at(eng));
i = field->getElementNames().indexOf("Roll");
val = floor(1-field->getDouble(i)/1.27);
m_aircraft->mrRollMixLevel->setValue(val);
if(eng>-1)
{
field = obj->getField(mixerVectors.at(eng));
i = field->getElementNames().indexOf("Roll");
val = floor(1-field->getDouble(i)/1.27);
m_aircraft->mrRollMixLevel->setValue(val);
}
}
} else if (frameType == "HexaX") {
// Motors 1/2/3 4/5/6 are: NE / E / SE / SW / W / NW
@ -1817,8 +1820,9 @@ void ConfigAirframeWidget::updateCustomAirframeUI()
we call additional methods for specific frames, so that we do not have a code
that is too heavy.
*/
void ConfigAirframeWidget::sendAircraftUpdate()
void ConfigAirframeWidget::updateObjectsFromWidgets()
{
qDebug()<<"updateObjectsFromWidgets";
QString airframeType = "Custom";
if (m_aircraft->aircraftType->currentText() == "Fixed Wing") {
// Save the curve (common to all Fixed wing frames)
@ -2123,31 +2127,9 @@ void ConfigAirframeWidget::sendAircraftUpdate()
}
}
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("ActuatorSettings")));
obj->updated();
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
obj->updated();
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("SystemSettings")));
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("SystemSettings")));
UAVObjectField* field = obj->getField(QString("AirframeType"));
field->setValue(airframeType);
obj->updated();
}
/**
Send airframe type to the board and request saving to SD card
*/
void ConfigAirframeWidget::saveAircraftUpdate()
{
// Send update so that the latest value is saved
sendAircraftUpdate();
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("SystemSettings")));
Q_ASSERT(obj);
saveObjectToSD(obj);
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("MixerSettings")));
saveObjectToSD(obj);
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("ActuatorSettings")));
saveObjectToSD(obj);
}

View File

@ -58,7 +58,6 @@ private:
void updateCustomAirframeUI();
bool setupMixer(double mixerFactors[8][3]);
void setupMotors(QList<QString> motorList);
virtual void enableControls(bool enable);
void resetField(UAVObjectField * field);
void resetMixer (MixerCurveWidget *mixer, int numElements, double maxvalue);
@ -74,9 +73,9 @@ private:
UAVObject::Metadata accInitialData;
private slots:
virtual void refreshValues();
void sendAircraftUpdate();
void saveAircraftUpdate();
virtual void refreshWidgetsValues();
void updateObjectsFromWidgets();
// void saveAircraftUpdate();
void setupAirframeUI(QString type);
void toggleAileron2(int index);
void toggleElevator2(int index);

View File

@ -37,6 +37,9 @@
#include <math.h>
#include <QMessageBox>
#include "mixersettings.h"
#include "systemsettings.h"
#define Pi 3.14159265358979323846
@ -1179,7 +1182,7 @@ void ConfigccpmWidget::requestccpmUpdate()
{
#define MaxAngleError 2
int MixerDataFromHeli[8][5];
QString MixerOutputType[8];
quint8 MixerOutputType[8];
int EngineChannel,TailRotorChannel,ServoChannels[4],ServoAngles[4],SortAngles[4],CalcAngles[4],ServoCurve2[4];
int NumServos=0;
double Collective=0.0;
@ -1191,39 +1194,45 @@ void ConfigccpmWidget::requestccpmUpdate()
if (updatingToHardware)return;
updatingFromHardware=TRUE;
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
int i,j;
UAVObjectField *field;
UAVDataObject* obj;
obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("SystemSettings")));
field = obj->getField(QString("GUIConfigData"));
GUIConfigData.UAVObject[0]=field->getValue(0).toUInt();
GUIConfigData.UAVObject[1]=field->getValue(1).toUInt();
UpdatCCPMUIFromOptions();
SystemSettings * systemSettings = SystemSettings::GetInstance(getObjectManager());
SystemSettings::DataFields systemSettingsData = systemSettings->getData();
Q_ASSERT(SystemSettings::GUICONFIGDATA_NUMELEM ==
(sizeof(GUIConfigData.UAVObject) / sizeof(GUIConfigData.UAVObject[0])));
for(i = 0; i < SystemSettings::GUICONFIGDATA_NUMELEM; i++)
GUIConfigData.UAVObject[i]=systemSettingsData.GUIConfigData[i];
UpdatCCPMUIFromOptions();
// Get existing mixer settings
MixerSettings * mixerSettings = MixerSettings::GetInstance(getObjectManager());
MixerSettings::DataFields mixerSettingsData = mixerSettings->getData();
obj = dynamic_cast<UAVDataObject*>(objManager->getObject(QString("MixerSettings")));
Q_ASSERT(obj);
//go through the user data and update the mixer matrix
for (i=0;i<8;i++)
for (j=0;j<5;j++)
{
field = obj->getField(tr( "Mixer%1Vector" ).arg(i+1));
//config the vector
for (j=0;j<5;j++)
{
MixerDataFromHeli[i][j] = field->getValue(j).toInt();
//field->setValue(m_ccpm->ccpmAdvancedSettingsTable->item(i,j+1)->text().toInt(),j);
}
}
for (i=0;i<8;i++)
{
field = obj->getField(tr( "Mixer%1Type" ).arg(i+1));
MixerOutputType[i] = field->getValue().toString();
MixerDataFromHeli[0][j] = mixerSettingsData.Mixer1Vector[j];
MixerDataFromHeli[1][j] = mixerSettingsData.Mixer2Vector[j];
MixerDataFromHeli[2][j] = mixerSettingsData.Mixer3Vector[j];
MixerDataFromHeli[3][j] = mixerSettingsData.Mixer4Vector[j];
MixerDataFromHeli[4][j] = mixerSettingsData.Mixer5Vector[j];
MixerDataFromHeli[5][j] = mixerSettingsData.Mixer6Vector[j];
MixerDataFromHeli[6][j] = mixerSettingsData.Mixer7Vector[j];
MixerDataFromHeli[7][j] = mixerSettingsData.Mixer8Vector[j];
}
MixerOutputType[0] = mixerSettingsData.Mixer1Type;
MixerOutputType[1] = mixerSettingsData.Mixer2Type;
MixerOutputType[2] = mixerSettingsData.Mixer3Type;
MixerOutputType[3] = mixerSettingsData.Mixer4Type;
MixerOutputType[4] = mixerSettingsData.Mixer5Type;
MixerOutputType[5] = mixerSettingsData.Mixer6Type;
MixerOutputType[6] = mixerSettingsData.Mixer7Type;
MixerOutputType[7] = mixerSettingsData.Mixer8Type;
EngineChannel =-1;
TailRotorChannel =-1;
for (j=0;j<5;j++)
@ -1239,7 +1248,7 @@ void ConfigccpmWidget::requestccpmUpdate()
for (i=0;i<8;i++)
{
//check if this is the engine... Throttle only
if ((MixerOutputType[i].compare("Motor")==0)&&
if ((MixerOutputType[i] == MixerSettings::MIXER1TYPE_MOTOR)&&
(MixerDataFromHeli[i][0]>0)&&//ThrottleCurve1
(MixerDataFromHeli[i][1]==0)&&//ThrottleCurve2
(MixerDataFromHeli[i][2]==0)&&//Roll
@ -1251,7 +1260,7 @@ void ConfigccpmWidget::requestccpmUpdate()
}
//check if this is the tail rotor... REVO and YAW
if ((MixerOutputType[i].compare("Servo")==0)&&
if ((MixerOutputType[i] == MixerSettings::MIXER1TYPE_SERVO)&&
//(MixerDataFromHeli[i][0]!=0)&&//ThrottleCurve1
(MixerDataFromHeli[i][1]==0)&&//ThrottleCurve2
(MixerDataFromHeli[i][2]==0)&&//Roll
@ -1264,7 +1273,7 @@ void ConfigccpmWidget::requestccpmUpdate()
m_ccpm->ccpmREVOspinBox->setValue((MixerDataFromHeli[i][0]*100)/127);
}
//check if this is a swashplate servo... Throttle is zero
if ((MixerOutputType[i].compare("Servo")==0)&&
if ((MixerOutputType[i] == MixerSettings::MIXER1TYPE_SERVO)&&
(MixerDataFromHeli[i][0]==0)&&//ThrottleCurve1
//(MixerDataFromHeli[i][1]==0)&&//ThrottleCurve2
//(MixerDataFromHeli[i][2]==0)&&//Roll
@ -1275,193 +1284,23 @@ void ConfigccpmWidget::requestccpmUpdate()
ServoCurve2[NumServos]=MixerDataFromHeli[i][1];//record the ThrottleCurve2 contribution to this servo
ServoAngles[NumServos]=NumServos*45;//make this 0 for the final version
//if (NumServos==0)m_ccpm->ccpmServoWChannel->setCurrentIndex(i);
//if (NumServos==1)m_ccpm->ccpmServoXChannel->setCurrentIndex(i);
//if (NumServos==2)m_ccpm->ccpmServoYChannel->setCurrentIndex(i);
//if (NumServos==3)m_ccpm->ccpmServoZChannel->setCurrentIndex(i);
NumServos++;
}
}
//just call it user angles for now....
/*
m_ccpm->ccpmType->setCurrentIndex(m_ccpm->ccpmType->findText("Custom - User Angles"));
if (NumServos>1)
{
if((ServoCurve2[0]==0)&&(ServoCurve2[1]==0)&&(ServoCurve2[2]==0)&&(ServoCurve2[3]==0))
{
//fixed pitch heli
isCCPM=0;
m_ccpm->ccpmCollectiveSlider->setValue(0);
Collective = 0.0;
}
if(ServoCurve2[0]==ServoCurve2[1])
{
if ((NumServos<3)||(ServoCurve2[1]==ServoCurve2[2]))
{
if ((NumServos<4)||(ServoCurve2[2]==ServoCurve2[3]))
{//all the servos have the same ThrottleCurve2 setting so this must be a CCPM config
isCCPM=1;
Collective = ((double)ServoCurve2[0]*100.00)/127.00;
m_ccpm->ccpmCollectiveSlider->setValue((int)Collective);
m_ccpm->ccpmCollectivespinBox->setValue((int)Collective);
}
}
}
}
else
{//must be a custom config... "Custom - Advanced Settings"
m_ccpm->ccpmType->setCurrentIndex(m_ccpm->ccpmType->findText("Custom - Advanced Settings"));
}
HeadRotation=0;
HeadRotation=m_ccpm->ccpmSingleServo->currentIndex();
//calculate the angles
for(j=0;j<NumServos;j++)
{
//MixerDataFromHeli[i][2]=(127.0*(1-CollectiveConstant)*sin((CorrectionAngle + ThisAngle[i])*Pi/180.00))));//Roll
//MixerDataFromHeli[i][3]=(127.0*(1-CollectiveConstant)*cos((CorrectionAngle + ThisAngle[i])*Pi/180.00))));//Pitch
a1=((double)MixerDataFromHeli[ServoChannels[j]][2]/(1.27*(100.0-Collective)));
a2=((double)MixerDataFromHeli[ServoChannels[j]][3]/(1.27*(100.0-Collective)));
ServoAngles[j]=fmod(360.0+atan2(-a1,a2)/(Pi/180.00),360.0);
//check the angles for one being a multiple of 90deg
if (fmod(ServoAngles[j],90)<MaxAngleError)
{
HeadRotation=ServoAngles[j]/90;
}
}
//set the head rotation
//m_ccpm->ccpmSingleServo->setCurrentIndex(HeadRotation);
//calculate the un rotated angles
for(j=0;j<NumServos;j++)
{
CalcAngles[j] = fmod(360.0+ServoAngles[j]-(double)HeadRotation*90.0,360.0);
}
//sort the calc angles do the smallest is first...brute force...
for(i=0;i<5;i++)
for(j=0;j<NumServos-1;j++)
{
if (CalcAngles[SortAngles[j]] > CalcAngles[SortAngles[j+1]])
{//swap the sorted angles
temp = SortAngles[j];
SortAngles[j]=SortAngles[j+1];
SortAngles[j+1]=temp;
}
}
//m_ccpm->ccpmAngleW->setValue(ServoAngles[SortAngles[0]]);
//m_ccpm->ccpmAngleX->setValue(ServoAngles[SortAngles[1]]);
//m_ccpm->ccpmAngleY->setValue(ServoAngles[SortAngles[2]]);
//m_ccpm->ccpmAngleZ->setValue(ServoAngles[SortAngles[3]]);
//m_ccpm->ccpmServoWChannel->setCurrentIndex(ServoChannels[SortAngles[0]]);
//m_ccpm->ccpmServoXChannel->setCurrentIndex(ServoChannels[SortAngles[1]]);
//m_ccpm->ccpmServoYChannel->setCurrentIndex(ServoChannels[SortAngles[2]]);
//m_ccpm->ccpmServoZChannel->setCurrentIndex(ServoChannels[SortAngles[3]]);
m_ccpm->ccpmServoWChannel->setCurrentIndex(ServoChannels[0]);
m_ccpm->ccpmServoXChannel->setCurrentIndex(ServoChannels[1]);
m_ccpm->ccpmServoYChannel->setCurrentIndex(ServoChannels[2]);
m_ccpm->ccpmServoZChannel->setCurrentIndex(ServoChannels[3]);
//Types << "CCPM 2 Servo 90º" << "CCPM 3 Servo 120º" << "CCPM 3 Servo 140º" << "FP 2 Servo 90º" << "Custom - User Angles" << "Custom - Advanced Settings" ;
//check this against known combinations
if (NumServos==2)
{
if ((fabs(CalcAngles[SortAngles[0]])<MaxAngleError)&&
(fabs(CalcAngles[SortAngles[1]]-90)<MaxAngleError))
{// two servo 90º
if (isCCPM)
{
m_ccpm->ccpmType->setCurrentIndex(m_ccpm->ccpmType->findText("CCPM 2 Servo 90º"));
UpdateType();
}
else
{
m_ccpm->ccpmType->setCurrentIndex(m_ccpm->ccpmType->findText("FP 2 Servo 90º"));
UpdateType();
}
}
}
if (NumServos==3)
{
if ((fabs(CalcAngles[SortAngles[0]])<MaxAngleError)&&
(fabs(CalcAngles[SortAngles[1]]-120)<MaxAngleError)&&
(fabs(CalcAngles[SortAngles[2]]-240)<MaxAngleError))
{// three servo 120º
if (isCCPM)
{
m_ccpm->ccpmType->setCurrentIndex(m_ccpm->ccpmType->findText("CCPM 3 Servo 120º"));
UpdateType();
}
else
{
m_ccpm->ccpmType->setCurrentIndex(m_ccpm->ccpmType->findText("FP 3 Servo 120º"));
UpdateType();
}
}
else if ((fabs(CalcAngles[SortAngles[0]])<MaxAngleError)&&
(fabs(CalcAngles[SortAngles[1]]-140)<MaxAngleError)&&
(fabs(CalcAngles[SortAngles[2]]-220)<MaxAngleError))
{// three servo 140º
if (isCCPM)
{
m_ccpm->ccpmType->setCurrentIndex(m_ccpm->ccpmType->findText("CCPM 3 Servo 140º"));
UpdateType();
}
else
{
m_ccpm->ccpmType->setCurrentIndex(m_ccpm->ccpmType->findText("FP 3 Servo 140º"));
UpdateType();
}
}
}
if (NumServos==4)
{
}
*/
//get the settings for the curve from the mixer settings
field = obj->getField(QString("ThrottleCurve1"));
for (i=0;i<5;i++)
{
m_ccpm->CurveSettings->item(i, 0)->setText(QString().sprintf("%.3f",field->getValue(i).toDouble()));
//m_ccpm->CurveSettings->item(i, 0)->setText(field->getValue(i).toString());
m_ccpm->CurveSettings->item(i, 0)->setText(QString().sprintf("%.3f",
mixerSettingsData.ThrottleCurve1[i]));
m_ccpm->CurveSettings->item(i, 1)->setText(QString().sprintf("%.3f",
mixerSettingsData.ThrottleCurve2[i]));
}
field = obj->getField(QString("ThrottleCurve2"));
for (i=0;i<5;i++)
{
m_ccpm->CurveSettings->item(i, 1)->setText(QString().sprintf("%.3f",field->getValue(i).toDouble()));
//m_ccpm->CurveSettings->item(i, 1)->setText(field->getValue(i).toString());
}
updatingFromHardware=FALSE;
UpdatCCPMUIFromOptions();
ccpmSwashplateUpdate();
}
@ -1499,7 +1338,7 @@ void ConfigccpmWidget::sendccpmUpdate()
//clear the output types
for (i=0;i<8;i++)
{
field = obj->getField(tr( "Mixer%1Type" ).arg( i+1 ));
field = obj->getField( QString( "Mixer%1Type" ).arg( i+1 ));
//clear the mixer type
field->setValue("Disabled");
}
@ -1520,7 +1359,7 @@ void ConfigccpmWidget::sendccpmUpdate()
if (MixerChannelData[i]<8)
{
//select the correct mixer for this config element
field = obj->getField(tr( "Mixer%1Type" ).arg( MixerChannelData[i]+1 ));
field = obj->getField(QString( "Mixer%1Type" ).arg( MixerChannelData[i]+1 ));
//set the mixer type
if (i==0)
{
@ -1532,7 +1371,7 @@ void ConfigccpmWidget::sendccpmUpdate()
}
//select the correct mixer for this config element
field = obj->getField(tr( "Mixer%1Vector" ).arg( MixerChannelData[i]+1 ));
field = obj->getField(QString( "Mixer%1Vector" ).arg( MixerChannelData[i]+1 ));
//config the vector
for (j=0;j<5;j++)
{

View File

@ -1,18 +1,19 @@
<RCC>
<qresource prefix="/configgadget">
<file>images/help2.png</file>
<file>images/XBee.svg</file>
<file>images/Airframe.png</file>
<file>images/Servo.png</file>
<file>images/ahrs-calib.svg</file>
<file>images/AHRS-v1.3.png</file>
<file>images/paper-plane.svg</file>
<file>images/curve-bg.svg</file>
<file>images/quad-shapes.svg</file>
<file>images/ccpm_setup.svg</file>
<file>images/PipXtreme.png</file>
<file>images/gyroscope.svg</file>
<file>images/Transmitter.png</file>
<file>images/help.png</file>
</qresource>
<qresource prefix="/configgadget">
<file>images/help2.png</file>
<file>images/Airframe.png</file>
<file>images/Servo.png</file>
<file>images/ahrs-calib.svg</file>
<file>images/AHRS-v1.3.png</file>
<file>images/paper-plane.svg</file>
<file>images/curve-bg.svg</file>
<file>images/quad-shapes.svg</file>
<file>images/ccpm_setup.svg</file>
<file>images/PipXtreme.png</file>
<file>images/Transmitter.png</file>
<file>images/help.png</file>
<file>images/coptercontrol.svg</file>
<file>images/hw_config.png</file>
<file>images/gyroscope.png</file>
</qresource>
</RCC>

View File

@ -33,9 +33,10 @@
#include "configinputwidget.h"
#include "configoutputwidget.h"
#include "configstabilizationwidget.h"
#include "configtelemetrywidget.h"
#include "config_pro_hw_widget.h"
#include "config_cc_hw_widget.h"
#include "defaultattitudewidget.h"
#include "defaulthwsettingswidget.h"
#include "uavobjectutilmanager.h"
#include <QDebug>
@ -51,34 +52,35 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent)
{
setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::MinimumExpanding);
ftw = new FancyTabWidget(this, true);
ftw = new MyTabbedStackWidget(this, true, true);
ftw->setIconSize(64);
QVBoxLayout *layout = new QVBoxLayout;
layout->setContentsMargins(0, 0, 0, 0);
layout->addWidget(ftw);
setLayout(layout);
// *********************
QWidget *qwd;
qwd = new DefaultHwSettingsWidget(this);
ftw->insertTab(ConfigGadgetWidget::hardware, qwd, QIcon(":/configgadget/images/hw_config.png"), QString("HW Settings"));
qwd = new ConfigAirframeWidget(this);
ftw->insertTab(0, qwd, QIcon(":/configgadget/images/Airframe.png"), QString("Aircraft"));
ftw->insertTab(ConfigGadgetWidget::aircraft, qwd, QIcon(":/configgadget/images/Airframe.png"), QString("Aircraft"));
qwd = new ConfigInputWidget(this);
ftw->insertTab(1, qwd, QIcon(":/configgadget/images/Transmitter.png"), QString("Input"));
ftw->insertTab(ConfigGadgetWidget::input, qwd, QIcon(":/configgadget/images/Transmitter.png"), QString("Input"));
qwd = new ConfigOutputWidget(this);
ftw->insertTab(2, qwd, QIcon(":/configgadget/images/Servo.png"), QString("Output"));
ftw->insertTab(ConfigGadgetWidget::output, qwd, QIcon(":/configgadget/images/Servo.png"), QString("Output"));
qwd = new DefaultAttitudeWidget(this);
ftw->insertTab(3, qwd, QIcon(":/configgadget/images/AHRS-v1.3.png"), QString("INS"));
ftw->insertTab(ConfigGadgetWidget::ins, qwd, QIcon(":/configgadget/images/AHRS-v1.3.png"), QString("INS"));
qwd = new ConfigStabilizationWidget(this);
ftw->insertTab(4, qwd, QIcon(":/configgadget/images/gyroscope.svg"), QString("Stabilization"));
ftw->insertTab(ConfigGadgetWidget::stabilization, qwd, QIcon(":/configgadget/images/gyroscope.png"), QString("Stabilization"));
qwd = new ConfigTelemetryWidget(this);
ftw->insertTab(5, qwd, QIcon(":/configgadget/images/XBee.svg"), QString("Telemetry"));
// qwd = new ConfigPipXtremeWidget(this);
@ -128,16 +130,24 @@ void ConfigGadgetWidget::onAutopilotConnect() {
if ((board & 0xff00) == 1024) {
// CopterControl family
// Delete the INS panel, replace with CC Panel:
ftw->setCurrentIndex(0);
ftw->removeTab(3);
ftw->setCurrentIndex(ConfigGadgetWidget::hardware);
ftw->removeTab(ConfigGadgetWidget::ins);
QWidget *qwd = new ConfigCCAttitudeWidget(this);
ftw->insertTab(3, qwd, QIcon(":/configgadget/images/AHRS-v1.3.png"), QString("Attitude"));
ftw->insertTab(ConfigGadgetWidget::ins, qwd, QIcon(":/configgadget/images/AHRS-v1.3.png"), QString("Attitude"));
ftw->removeTab(ConfigGadgetWidget::hardware);
qwd = new ConfigCCHWWidget(this);
ftw->insertTab(ConfigGadgetWidget::hardware, qwd, QIcon(":/configgadget/images/hw_config.png"), QString("HW Settings"));
ftw->setCurrentIndex(ConfigGadgetWidget::hardware);
} else if ((board & 0xff00) == 256 ) {
// Mainboard family
ftw->setCurrentIndex(0);
ftw->removeTab(3);
ftw->setCurrentIndex(ConfigGadgetWidget::hardware);
ftw->removeTab(ConfigGadgetWidget::ins);
QWidget *qwd = new ConfigAHRSWidget(this);
ftw->insertTab(3, qwd, QIcon(":/configgadget/images/AHRS-v1.3.png"), QString("INS"));
ftw->insertTab(ConfigGadgetWidget::ins, qwd, QIcon(":/configgadget/images/AHRS-v1.3.png"), QString("INS"));
ftw->removeTab(ConfigGadgetWidget::hardware);
qwd = new ConfigProHWWidget(this);
ftw->insertTab(ConfigGadgetWidget::hardware, qwd, QIcon(":/configgadget/images/hw_config.png"), QString("HW Settings"));
ftw->setCurrentIndex(ConfigGadgetWidget::hardware);
}
}
emit autopilotConnected();

View File

@ -38,7 +38,8 @@
#include <QTextBrowser>
#include "utils/pathutils.h"
#include "fancytabwidget.h"
//#include "fancytabwidget.h"
#include "utils/mytabbedstackwidget.h"
class ConfigGadgetWidget: public QWidget
@ -49,6 +50,7 @@ class ConfigGadgetWidget: public QWidget
public:
ConfigGadgetWidget(QWidget *parent = 0);
~ConfigGadgetWidget();
enum widgetTabs {hardware=0, aircraft, input, output, ins, stabilization};
public slots:
void onAutopilotConnect();
@ -60,8 +62,7 @@ signals:
protected:
void resizeEvent(QResizeEvent * event);
FancyTabWidget *ftw;
MyTabbedStackWidget *ftw;
};
#endif // CONFIGGADGETWIDGET_H

View File

@ -110,10 +110,7 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) : ConfigTaskWidget(parent)
// Get the receiver types supported by OpenPilot and fill the corresponding
// dropdown menu:
obj = dynamic_cast<UAVDataObject*>(objManager->getObject(QString("ManualControlSettings")));
QString fieldName = QString("InputMode");
UAVObjectField *field = obj->getField(fieldName);
m_config->receiverType->addItems(field->getOptions());
UAVObjectField * field;
// Fill in the dropdown menus for the channel RC Input assignement.
QStringList channelsList;
channelsList << "None";
@ -263,7 +260,7 @@ void ConfigInputWidget::refreshValues()
// Update receiver type
field = obj->getField(QString("InputMode"));
m_config->receiverType->setCurrentIndex(m_config->receiverType->findText(field->getValue().toString()));
m_config->receiverType->setText(field->getValue().toString());
// Reset all channel assignement dropdowns:
foreach (QComboBox *combo, inChannelAssign) {
@ -331,11 +328,6 @@ void ConfigInputWidget::sendRCInputUpdate()
for (int i = 0; i < 8; i++)
field->setValue(inSliders[i]->value(), i);
// Set RC Receiver type:
fieldName = QString("InputMode");
field = obj->getField(fieldName);
field->setValue(m_config->receiverType->currentText());
// Set Roll/Pitch/Yaw/Etc assignement:
// Rule: if two channels have the same setting (which is wrong!) the higher channel
// will get the setting.
@ -706,7 +698,7 @@ void ConfigInputWidget::receiverHelp()
unassigned.append("FlightMode");
}
if(unassigned.length()>0)
m_config->lblMissingInputs->setText(QString("Channels left to assign:")+unassigned);
m_config->lblMissingInputs->setText(QString("Channels left to assign: ")+unassigned);
else
m_config->lblMissingInputs->setText("");
}

View File

@ -230,6 +230,8 @@ void ConfigStabilizationWidget::refreshValues()
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);
}
@ -277,6 +279,10 @@ 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;
stabSettings->setData(stabData); // this is atomic
}

View File

@ -28,13 +28,72 @@
#include <QtGui/QWidget>
ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent)
ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent),smartsave(NULL),dirty(false)
{
pm = ExtensionSystem::PluginManager::instance();
objManager = pm->getObject<UAVObjectManager>();
connect(parent, SIGNAL(autopilotConnected()),this, SLOT(onAutopilotConnect()));
connect(parent, SIGNAL(autopilotDisconnected()),this, SLOT(onAutopilotDisconnect()));
}
void ConfigTaskWidget::addWidget(QWidget * widget)
{
addUAVObjectToWidgetRelation("","",widget);
}
void ConfigTaskWidget::addUAVObject(QString objectName)
{
addUAVObjectToWidgetRelation(objectName,"",NULL);
}
void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget * widget)
{
UAVObject *obj=NULL;
UAVObjectField *_field=NULL;
if(!object.isEmpty())
obj = objManager->getObject(QString(object));
connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues()));
//smartsave->addObject(obj);
if(!field.isEmpty() && obj)
_field = obj->getField(QString(field));
objectToWidget * ow=new objectToWidget();
ow->field=_field;
ow->object=obj;
ow->widget=widget;
objOfInterest.append(ow);
if(obj)
smartsave->addObject(obj);
if(widget==NULL)
{
// do nothing
}
else if(QComboBox * cb=qobject_cast<QComboBox *>(widget))
{
connect(cb,SIGNAL(currentIndexChanged(int)),this,SLOT(widgetsContentsChanged()));
}
else if(QSlider * cb=qobject_cast<QSlider *>(widget))
{
connect(cb,SIGNAL(sliderMoved(int)),this,SLOT(widgetsContentsChanged()));
}
else if(MixerCurveWidget * cb=qobject_cast<MixerCurveWidget *>(widget))
{
connect(cb,SIGNAL(curveUpdated(QList<double>,double)),this,SLOT(widgetsContentsChanged()));
}
else if(QTableWidget * cb=qobject_cast<QTableWidget *>(widget))
{
connect(cb,SIGNAL(cellChanged(int,int)),this,SLOT(widgetsContentsChanged()));
}
else if(QSpinBox * cb=qobject_cast<QSpinBox *>(widget))
{
connect(cb,SIGNAL(valueChanged(int)),this,SLOT(widgetsContentsChanged()));
}
else if(QDoubleSpinBox * cb=qobject_cast<QDoubleSpinBox *>(widget))
{
connect(cb,SIGNAL(valueChanged(double)),this,SLOT(widgetsContentsChanged()));
}
}
ConfigTaskWidget::~ConfigTaskWidget()
{
// Do nothing
delete smartsave;
}
void ConfigTaskWidget::saveObjectToSD(UAVObject *obj)
@ -73,9 +132,125 @@ void ConfigTaskWidget::onAutopilotDisconnect()
void ConfigTaskWidget::onAutopilotConnect()
{
enableControls(true);
refreshValues();
refreshWidgetsValues();
}
void ConfigTaskWidget::populateWidgets()
{
foreach(objectToWidget * ow,objOfInterest)
{
if(ow->object==NULL || ow->field==NULL)
{
// do nothing
}
else if(QComboBox * cb=qobject_cast<QComboBox *>(ow->widget))
{
cb->addItems(ow->field->getOptions());
cb->setCurrentIndex(cb->findText(ow->field->getValue().toString()));
}
else if(QLabel * cb=qobject_cast<QLabel *>(ow->widget))
{
cb->setText(ow->field->getValue().toString());
}
}
dirty=false;
}
void ConfigTaskWidget::refreshWidgetsValues()
{
foreach(objectToWidget * ow,objOfInterest)
{
if(ow->object==NULL || ow->field==NULL)
{
//do nothing
}
else if(QComboBox * cb=qobject_cast<QComboBox *>(ow->widget))
{
cb->setCurrentIndex(cb->findText(ow->field->getValue().toString()));
}
else if(QLabel * cb=qobject_cast<QLabel *>(ow->widget))
{
cb->setText(ow->field->getValue().toString());
}
}
}
void ConfigTaskWidget::updateObjectsFromWidgets()
{
foreach(objectToWidget * ow,objOfInterest)
{
if(ow->object==NULL || ow->field==NULL)
{
//do nothing
}
else if(QComboBox * cb=qobject_cast<QComboBox *>(ow->widget))
{
ow->field->setValue(cb->currentText());
}
else if(QLabel * cb=qobject_cast<QLabel *>(ow->widget))
{
ow->field->setValue(cb->text());
}
}
}
void ConfigTaskWidget::setupButtons(QPushButton *update, QPushButton *save)
{
smartsave=new smartSaveButton(update,save);
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()));
}
void ConfigTaskWidget::enableControls(bool enable)
{
if(smartsave)
smartsave->enableControls(enable);
}
void ConfigTaskWidget::widgetsContentsChanged()
{
dirty=true;
}
void ConfigTaskWidget::clearDirty()
{
dirty=false;
}
bool ConfigTaskWidget::isDirty()
{
return dirty;
}
void ConfigTaskWidget::refreshValues()
{
}
void ConfigTaskWidget::disableObjUpdates()
{
foreach(objectToWidget * obj,objOfInterest)
{
if(obj->object)
disconnect(obj->object, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues()));
}
}
void ConfigTaskWidget::enableObjUpdates()
{
foreach(objectToWidget * obj,objOfInterest)
{
if(obj->object)
connect(obj->object, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues()));
}
}
/**

View File

@ -35,28 +35,56 @@
#include <QQueue>
#include <QtGui/QWidget>
#include <QList>
#include <QLabel>
#include "smartsavebutton.h"
#include "mixercurvewidget.h"
#include <QTableWidget>
#include <QDoubleSpinBox>
#include <QSpinBox>
class ConfigTaskWidget: public QWidget
{
Q_OBJECT
public:
struct objectToWidget
{
UAVObject * object;
UAVObjectField * field;
QWidget * widget;
};
ConfigTaskWidget(QWidget *parent = 0);
~ConfigTaskWidget();
void saveObjectToSD(UAVObject *obj);
UAVObjectManager* getObjectManager();
static double listMean(QList<double> list);
void addUAVObject(QString objectName);
void addWidget(QWidget * widget);
void addUAVObjectToWidgetRelation(QString object,QString field,QWidget * widget);
void setupButtons(QPushButton * update,QPushButton * save);
bool isDirty();
public slots:
void onAutopilotDisconnect();
void onAutopilotConnect();
private slots:
virtual void refreshValues() = 0;
virtual void refreshValues();
virtual void updateObjectsFromWidgets();
private:
virtual void enableControls(bool enable) = 0;
QList <objectToWidget*> objOfInterest;
ExtensionSystem::PluginManager *pm;
UAVObjectManager *objManager;
smartSaveButton *smartsave;
bool dirty;
protected slots:
virtual void disableObjUpdates();
virtual void enableObjUpdates();
virtual void clearDirty();
virtual void widgetsContentsChanged();
virtual void populateWidgets();
virtual void refreshWidgetsValues();
protected:
virtual void enableControls(bool enable);
};

View File

@ -1,111 +0,0 @@
/**
******************************************************************************
*
* @file configtelemetrywidget.h
* @author E. Lafargue & The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @addtogroup GCSPlugins GCS Plugins
* @{
* @addtogroup ConfigPlugin Config Plugin
* @{
* @brief The Configuration Gadget used to update settings in the firmware
*****************************************************************************/
/*
* 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 "configtelemetrywidget.h"
#include <QDebug>
#include <QStringList>
#include <QtGui/QWidget>
#include <QtGui/QTextEdit>
#include <QtGui/QVBoxLayout>
#include <QtGui/QPushButton>
ConfigTelemetryWidget::ConfigTelemetryWidget(QWidget *parent) : ConfigTaskWidget(parent)
{
m_telemetry = new Ui_TelemetryWidget();
m_telemetry->setupUi(this);
// Now connect the widget to the ManualControlCommand / Channel UAVObject
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
UAVObject *obj = objManager->getObject(QString("TelemetrySettings"));
UAVObjectField *field = obj->getField(QString("Speed"));
m_telemetry->telemetrySpeed->addItems(field->getOptions());
connect(m_telemetry->saveTelemetryToSD, SIGNAL(clicked()), this, SLOT(saveTelemetryUpdate()));
connect(m_telemetry->saveTelemetryToRAM, SIGNAL(clicked()), this, SLOT(sendTelemetryUpdate()));
connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshValues()));
enableControls(false);
refreshValues();
connect(parent, SIGNAL(autopilotConnected()),this, SLOT(onAutopilotConnect()));
connect(parent, SIGNAL(autopilotDisconnected()),this, SLOT(onAutopilotDisconnect()));
}
ConfigTelemetryWidget::~ConfigTelemetryWidget()
{
// Do nothing
}
/*******************************
* Telemetry Settings
*****************************/
void ConfigTelemetryWidget::enableControls(bool enable)
{
m_telemetry->saveTelemetryToSD->setEnabled(enable);
//m_telemetry->saveTelemetryToRAM->setEnabled(enable);
}
/**
Request telemetry settings from the board
*/
void ConfigTelemetryWidget::refreshValues()
{
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
UAVObjectManager *objManager = pm->getObject<UAVObjectManager>();
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(objManager->getObject(QString("TelemetrySettings")));
Q_ASSERT(obj);
UAVObjectField *field = obj->getField(QString("Speed"));
m_telemetry->telemetrySpeed->setCurrentIndex(m_telemetry->telemetrySpeed->findText(field->getValue().toString()));
}
/**
Send telemetry settings to the board
*/
void ConfigTelemetryWidget::sendTelemetryUpdate()
{
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("TelemetrySettings")));
Q_ASSERT(obj);
UAVObjectField* field = obj->getField(QString("Speed"));
field->setValue(m_telemetry->telemetrySpeed->currentText());
obj->updated();
}
/**
Send telemetry settings to the board and request saving to SD card
*/
void ConfigTelemetryWidget::saveTelemetryUpdate()
{
// Send update so that the latest value is saved
sendTelemetryUpdate();
UAVDataObject* obj = dynamic_cast<UAVDataObject*>(getObjectManager()->getObject(QString("TelemetrySettings")));
Q_ASSERT(obj);
saveObjectToSD(obj);
}

Some files were not shown because too many files have changed in this diff Show More