From 5895468f08a613a88e9e1754f8630c8ddd309bbe Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Wed, 3 Aug 2016 17:31:41 +0200 Subject: [PATCH 01/20] LP-298 Port Ibus Input driver from dRonin - Not tested --- flight/make/apps-defs.mk | 1 + flight/modules/Receiver/receiver.c | 3 + flight/pios/common/pios_ibus.c | 256 ++++++++++++++++++ flight/pios/inc/pios_ibus.h | 38 +++ flight/pios/inc/pios_ibus_priv.h | 51 ++++ flight/pios/pios.h | 4 + .../boards/coptercontrol/board_hw_defs.c | 44 +++ .../coptercontrol/firmware/inc/pios_config.h | 1 + .../coptercontrol/firmware/pios_board.c | 23 +- .../targets/boards/coptercontrol/pios_board.h | 6 + .../targets/boards/revolution/board_hw_defs.c | 49 ++++ .../revolution/firmware/inc/pios_config.h | 1 + .../boards/revolution/firmware/pios_board.c | 22 ++ .../targets/boards/revonano/board_hw_defs.c | 51 +++- .../boards/revonano/firmware/pios_board.c | 24 +- flight/targets/boards/sparky2/board_hw_defs.c | 80 ++++++ .../boards/sparky2/firmware/inc/pios_config.h | 1 + .../boards/sparky2/firmware/pios_board.c | 34 ++- .../src/plugins/config/inputchannelform.cpp | 3 + shared/uavobjectdefinition/hwsettings.xml | 8 +- .../manualcontrolsettings.xml | 2 +- .../uavobjectdefinition/receiveractivity.xml | 2 +- 22 files changed, 694 insertions(+), 10 deletions(-) create mode 100644 flight/pios/common/pios_ibus.c create mode 100644 flight/pios/inc/pios_ibus.h create mode 100644 flight/pios/inc/pios_ibus_priv.h diff --git a/flight/make/apps-defs.mk b/flight/make/apps-defs.mk index 929efafdc..d4d89ce31 100644 --- a/flight/make/apps-defs.mk +++ b/flight/make/apps-defs.mk @@ -93,6 +93,7 @@ SRC += $(PIOSCOMMON)/pios_sbus.c SRC += $(PIOSCOMMON)/pios_hott.c SRC += $(PIOSCOMMON)/pios_srxl.c SRC += $(PIOSCOMMON)/pios_exbus.c +SRC += $(PIOSCOMMON)/pios_ibus.c SRC += $(PIOSCOMMON)/pios_sdcard.c SRC += $(PIOSCOMMON)/pios_sensors.c SRC += $(PIOSCOMMON)/pios_openlrs.c diff --git a/flight/modules/Receiver/receiver.c b/flight/modules/Receiver/receiver.c index 2414c8115..900e1194c 100644 --- a/flight/modules/Receiver/receiver.c +++ b/flight/modules/Receiver/receiver.c @@ -670,6 +670,9 @@ static bool updateRcvrActivityCompare(uint32_t rcvr_id, struct rcvr_activity_fsm case MANUALCONTROLSETTINGS_CHANNELGROUPS_SRXL: group = RECEIVERACTIVITY_ACTIVEGROUP_SRXL; break; + case MANUALCONTROLSETTINGS_CHANNELGROUPS_IBUS: + group = RECEIVERACTIVITY_ACTIVEGROUP_IBUS; + break; case MANUALCONTROLSETTINGS_CHANNELGROUPS_GCS: group = RECEIVERACTIVITY_ACTIVEGROUP_GCS; break; diff --git a/flight/pios/common/pios_ibus.c b/flight/pios/common/pios_ibus.c new file mode 100644 index 000000000..5f3300d53 --- /dev/null +++ b/flight/pios/common/pios_ibus.c @@ -0,0 +1,256 @@ +/** + ****************************************************************************** + * @file pios_ibus.c + * @author dRonin, http://dRonin.org/, Copyright (C) 2016 + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_IBus PiOS IBus receiver driver + * @{ + * @brief Receives and decodes IBus protocol reciever packets + *****************************************************************************/ +/* + * 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 + * + * Additional note on redistribution: The copyright and license notices above + * must be maintained in each individual source file that is a derivative work + * of this source file; otherwise redistribution is prohibited. + */ + +#include "pios_ibus_priv.h" + +#ifdef PIOS_INCLUDE_IBUS + +// private +#define PIOS_IBUS_CHANNELS 10 +// 1 sync byte, 1 unknown byte, 10x channels (uint16_t), 8 unknown bytes, 2 crc bytes +#define PIOS_IBUS_BUFLEN (1 + 1 + PIOS_IBUS_CHANNELS * 2 + 8 + 2) +#define PIOS_IBUS_SYNCBYTE 0x20 +#define PIOS_IBUS_MAGIC 0x84fd9a39 + +/** + * @brief IBus receiver driver internal state data + */ +struct pios_ibus_dev { + uint32_t magic; + int buf_pos; + int rx_timer; + int failsafe_timer; + uint16_t checksum; + uint16_t channel_data[PIOS_IBUS_CHANNELS]; + uint8_t rx_buf[PIOS_IBUS_BUFLEN]; +}; + +/** + * @brief Allocates a driver instance + * @retval pios_ibus_dev pointer on success, NULL on failure + */ +static struct pios_ibus_dev *PIOS_IBUS_Alloc(void); +/** + * @brief Validate a driver instance + * @param[in] dev device driver instance pointer + * @retval true on success, false on failure + */ +static bool PIOS_IBUS_Validate(const struct pios_ibus_dev *ibus_dev); +/** + * @brief Read a channel from the last received frame + * @param[in] id Driver instance + * @param[in] channel 0-based channel index + * @retval raw channel value, or error value (see pios_rcvr.h) + */ +static int32_t PIOS_IBUS_Read(uint32_t id, uint8_t channel); +/** + * @brief Set all channels in the last frame buffer to a given value + * @param[in] dev Driver instance + * @param[in] value channel value + */ +static void PIOS_IBUS_SetAllChannels(struct pios_ibus_dev *ibus_dev, uint16_t value); +/** + * @brief Serial receive callback + * @param[in] context Driver instance handle + * @param[in] buf Receive buffer + * @param[in] buf_len Number of bytes available + * @param[out] headroom Number of bytes remaining in internal buffer + * @param[out] task_woken Did we awake a task? + * @retval Number of bytes consumed from the buffer + */ +static uint16_t PIOS_IBUS_Receive(uint32_t context, uint8_t *buf, uint16_t buf_len, + uint16_t *headroom, bool *task_woken); +/** + * @brief Reset the internal receive buffer state + * @param[in] ibus_dev device driver instance pointer + */ +static void PIOS_IBUS_ResetBuffer(struct pios_ibus_dev *ibus_dev); +/** + * @brief Unpack a frame from the internal receive buffer to the channel buffer + * @param[in] ibus_dev device driver instance pointer + */ +static void PIOS_IBUS_UnpackFrame(struct pios_ibus_dev *ibus_dev); +/** + * @brief RTC tick callback + * @param[in] context Driver instance handle + */ +static void PIOS_IBUS_Supervisor(uint32_t context); + +// public +const struct pios_rcvr_driver pios_ibus_rcvr_driver = { + .read = PIOS_IBUS_Read, +}; + + +static struct pios_ibus_dev *PIOS_IBUS_Alloc(void) +{ + struct pios_ibus_dev *ibus_dev; + + ibus_dev = (struct pios_ibus_dev *)pios_malloc(sizeof(*ibus_dev)); + + if (!ibus_dev) { + return NULL; + } + + memset(ibus_dev, 0, sizeof(*ibus_dev)); + ibus_dev->magic = PIOS_IBUS_MAGIC; + + return ibus_dev; +} + +static bool PIOS_IBUS_Validate(const struct pios_ibus_dev *ibus_dev) +{ + return ibus_dev && ibus_dev->magic == PIOS_IBUS_MAGIC; +} + +int32_t PIOS_IBUS_Init(uint32_t *ibus_id, const struct pios_com_driver *driver, + uint32_t lower_id) +{ + struct pios_ibus_dev *ibus_dev = PIOS_IBUS_Alloc(); + + if (!ibus_dev) { + return -1; + } + + *ibus_id = (uint32_t)ibus_dev; + + PIOS_IBUS_SetAllChannels(ibus_dev, PIOS_RCVR_INVALID); + + if (!PIOS_RTC_RegisterTickCallback(PIOS_IBUS_Supervisor, *ibus_id)) { + PIOS_Assert(0); + } + + (driver->bind_rx_cb)(lower_id, PIOS_IBUS_Receive, *ibus_id); + + return 0; +} + +static int32_t PIOS_IBUS_Read(uint32_t context, uint8_t channel) +{ + if (channel > PIOS_IBUS_CHANNELS) { + return PIOS_RCVR_INVALID; + } + + struct pios_ibus_dev *ibus_dev = (struct pios_ibus_dev *)context; + if (!PIOS_IBUS_Validate(ibus_dev)) { + return PIOS_RCVR_NODRIVER; + } + + return ibus_dev->channel_data[channel]; +} + +static void PIOS_IBUS_SetAllChannels(struct pios_ibus_dev *ibus_dev, uint16_t value) +{ + for (int i = 0; i < PIOS_IBUS_CHANNELS; i++) { + ibus_dev->channel_data[i] = value; + } +} + +static uint16_t PIOS_IBUS_Receive(uint32_t context, uint8_t *buf, uint16_t buf_len, + uint16_t *headroom, bool *task_woken) +{ + struct pios_ibus_dev *ibus_dev = (struct pios_ibus_dev *)context; + + if (!PIOS_IBUS_Validate(ibus_dev)) { + goto out_fail; + } + + for (int i = 0; i < buf_len; i++) { + if (ibus_dev->buf_pos == 0 && buf[i] != PIOS_IBUS_SYNCBYTE) { + continue; + } + + ibus_dev->rx_buf[ibus_dev->buf_pos++] = buf[i]; + if (ibus_dev->buf_pos <= PIOS_IBUS_BUFLEN - 2) { + ibus_dev->checksum -= buf[i]; + } else if (ibus_dev->buf_pos == PIOS_IBUS_BUFLEN) { + PIOS_IBUS_UnpackFrame(ibus_dev); + } + } + + ibus_dev->rx_timer = 0; + + *headroom = PIOS_IBUS_BUFLEN - ibus_dev->buf_pos; + *task_woken = false; + return buf_len; + +out_fail: + *headroom = 0; + *task_woken = false; + return 0; +} + +static void PIOS_IBUS_ResetBuffer(struct pios_ibus_dev *ibus_dev) +{ + ibus_dev->checksum = 0xffff; + ibus_dev->buf_pos = 0; +} + +static void PIOS_IBUS_UnpackFrame(struct pios_ibus_dev *ibus_dev) +{ + uint16_t rxsum = ibus_dev->rx_buf[PIOS_IBUS_BUFLEN - 1] << 8 | + ibus_dev->rx_buf[PIOS_IBUS_BUFLEN - 2]; + + if (ibus_dev->checksum != rxsum) { + goto out_fail; + } + + uint16_t *chan = (uint16_t *)&ibus_dev->rx_buf[2]; + for (int i = 0; i < PIOS_IBUS_CHANNELS; i++) { + ibus_dev->channel_data[i] = *chan++; + } + + ibus_dev->failsafe_timer = 0; + +out_fail: + PIOS_IBUS_ResetBuffer(ibus_dev); +} + +static void PIOS_IBUS_Supervisor(uint32_t context) +{ + struct pios_ibus_dev *ibus_dev = (struct pios_ibus_dev *)context; + + PIOS_Assert(PIOS_IBUS_Validate(ibus_dev)); + + if (++ibus_dev->rx_timer > 3) { + PIOS_IBUS_ResetBuffer(ibus_dev); + } + + if (++ibus_dev->failsafe_timer > 32) { + PIOS_IBUS_SetAllChannels(ibus_dev, PIOS_RCVR_TIMEOUT); + } +} + +#endif // PIOS_INCLUDE_IBUS + +/** + * @} + * @} + */ diff --git a/flight/pios/inc/pios_ibus.h b/flight/pios/inc/pios_ibus.h new file mode 100644 index 000000000..7c27d26d2 --- /dev/null +++ b/flight/pios/inc/pios_ibus.h @@ -0,0 +1,38 @@ +/** + ****************************************************************************** + * + * @file pios_ibus.h + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * dRonin, http://dRonin.org/, Copyright (C) 2016 + * @brief FlySky IBus 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_IBUS_H +#define PIOS_IBUS_H + +/* Global Types */ + +/* Public Functions */ + +#endif /* PIOS_IBUS_H */ + +/** + * @} + * @} + */ diff --git a/flight/pios/inc/pios_ibus_priv.h b/flight/pios/inc/pios_ibus_priv.h new file mode 100644 index 000000000..d0a9146f6 --- /dev/null +++ b/flight/pios/inc/pios_ibus_priv.h @@ -0,0 +1,51 @@ +/** + ****************************************************************************** + * @file pios_ibus_priv.h + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * dRonin, http://dRonin.org/, Copyright (C) 2016 + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_IBus IBus receiver functions + * @{ + * @brief Receives and decodes IBus protocol receiver packets + *****************************************************************************/ +/* + * 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 + * + * Additional note on redistribution: The copyright and license notices above + * must be maintained in each individual source file that is a derivative work + * of this source file; otherwise redistribution is prohibited. + */ + + +#ifndef PIOS_IBUS_PRIV_H +#define PIOS_IBUS_PRIV_H + +#include +#include + +/* IBUS receiver instance configuration */ +extern const struct pios_rcvr_driver pios_ibus_rcvr_driver; + +extern int32_t PIOS_IBUS_Init(uint32_t *ibus_id, + const struct pios_com_driver *driver, + uint32_t lower_id); + +#endif // PIOS_IBUS_PRIV_H + +/** + * @} + * @} + */ diff --git a/flight/pios/pios.h b/flight/pios/pios.h index fca43089b..3050b9c6f 100644 --- a/flight/pios/pios.h +++ b/flight/pios/pios.h @@ -241,6 +241,10 @@ extern "C" { #include #endif +#ifdef PIOS_INCLUDE_IBUS +#include +#endif + /* PIOS abstract receiver interface */ #ifdef PIOS_INCLUDE_RCVR #include diff --git a/flight/targets/boards/coptercontrol/board_hw_defs.c b/flight/targets/boards/coptercontrol/board_hw_defs.c index b693a7e9b..4222540ef 100644 --- a/flight/targets/boards/coptercontrol/board_hw_defs.c +++ b/flight/targets/boards/coptercontrol/board_hw_defs.c @@ -1151,6 +1151,50 @@ static const struct pios_usart_cfg pios_usart_srxl_flexi_cfg = { #endif /* PIOS_INCLUDE_SRXL */ +#if defined(PIOS_INCLUDE_IBUS) +/* + * IBUS USART + */ +#include + +static const struct pios_usart_cfg pios_usart_ibus_flexi_cfg = { + .regs = USART3, + .init = { + .USART_BaudRate = 115200, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = USART3_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_11, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_IPU, + }, + }, + .tx = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_IN_FLOATING, + }, + }, +}; + +#endif /* PIOS_INCLUDE_IBUS */ + #if defined(PIOS_INCLUDE_SBUS) /* * S.Bus USART diff --git a/flight/targets/boards/coptercontrol/firmware/inc/pios_config.h b/flight/targets/boards/coptercontrol/firmware/inc/pios_config.h index 1d4bcebbe..a6f521c81 100644 --- a/flight/targets/boards/coptercontrol/firmware/inc/pios_config.h +++ b/flight/targets/boards/coptercontrol/firmware/inc/pios_config.h @@ -106,6 +106,7 @@ #define PIOS_INCLUDE_EXBUS #define PIOS_INCLUDE_SRXL #define PIOS_INCLUDE_HOTT +#define PIOS_INCLUDE_IBUS /* #define PIOS_INCLUDE_GCSRCVR */ /* #define PIOS_INCLUDE_OPLINKRCVR */ diff --git a/flight/targets/boards/coptercontrol/firmware/pios_board.c b/flight/targets/boards/coptercontrol/firmware/pios_board.c index 25486b94d..820211c1d 100644 --- a/flight/targets/boards/coptercontrol/firmware/pios_board.c +++ b/flight/targets/boards/coptercontrol/firmware/pios_board.c @@ -382,7 +382,6 @@ void PIOS_Board_Init(void) break; case HWSETTINGS_USB_VCPPORT_USBTELEMETRY: #if defined(PIOS_INCLUDE_COM) - { uint32_t pios_usb_cdc_id; if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) { @@ -670,6 +669,28 @@ void PIOS_Board_Init(void) #endif /* PIOS_INCLUDE_SRXL */ break; + case HWSETTINGS_CC_FLEXIPORT_IBUS: +#if defined(PIOS_INCLUDE_IBUS) + { + uint32_t pios_usart_ibus_id; + if (PIOS_USART_Init(&pios_usart_ibus_id, &pios_usart_ibus_flexi_cfg)) { + PIOS_Assert(0); + } + + uint32_t pios_ibus_id; + if (PIOS_IBUS_Init(&pios_ibus_id, &pios_usart_com_driver, pios_usart_ibus_id)) { + PIOS_Assert(0); + } + + uint32_t pios_ibus_rcvr_id; + if (PIOS_RCVR_Init(&pios_ibus_rcvr_id, &pios_ibus_rcvr_driver, pios_ibus_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_IBUS] = pios_ibus_rcvr_id; + } +#endif /* PIOS_INCLUDE_IBUS */ + break; + case HWSETTINGS_CC_FLEXIPORT_DEBUGCONSOLE: #if defined(PIOS_INCLUDE_COM) #if defined(PIOS_INCLUDE_DEBUG_CONSOLE) diff --git a/flight/targets/boards/coptercontrol/pios_board.h b/flight/targets/boards/coptercontrol/pios_board.h index bfbb91819..1750b4d9a 100644 --- a/flight/targets/boards/coptercontrol/pios_board.h +++ b/flight/targets/boards/coptercontrol/pios_board.h @@ -272,6 +272,12 @@ extern uint32_t pios_com_mavlink_id; #define PIOS_SRXL_MAX_DEVS 1 #define PIOS_SRXL_NUM_INPUTS 16 +// ------------------------- +// Receiver FlySky IBus input +// ------------------------- +#define PIOS_IBUS_MAX_DEVS 1 +#define PIOS_IBUS_NUM_INPUTS 10 + // ------------------------- // Servo outputs // ------------------------- diff --git a/flight/targets/boards/revolution/board_hw_defs.c b/flight/targets/boards/revolution/board_hw_defs.c index 7218aa4a0..ac37cdbe0 100644 --- a/flight/targets/boards/revolution/board_hw_defs.c +++ b/flight/targets/boards/revolution/board_hw_defs.c @@ -1171,6 +1171,55 @@ static const struct pios_usart_cfg pios_usart_hott_flexi_cfg = { #endif /* PIOS_INCLUDE_HOTT */ +#if defined(PIOS_INCLUDE_IBUS) +/* + * IBUS USART + */ +#include + +static const struct pios_usart_cfg pios_usart_ibus_flexi_cfg = { + .regs = USART3, + .remap = GPIO_AF_USART3, + .init = { + .USART_BaudRate = 115200, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = USART3_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_11, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + .tx = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, +}; + +#endif /* PIOS_INCLUDE_IBUS */ + #if defined(PIOS_INCLUDE_EXBUS) /* * EXBUS USART diff --git a/flight/targets/boards/revolution/firmware/inc/pios_config.h b/flight/targets/boards/revolution/firmware/inc/pios_config.h index d040e90d5..efe32a4be 100644 --- a/flight/targets/boards/revolution/firmware/inc/pios_config.h +++ b/flight/targets/boards/revolution/firmware/inc/pios_config.h @@ -107,6 +107,7 @@ #define PIOS_INCLUDE_SRXL #define PIOS_INCLUDE_HOTT #define PIOS_INCLUDE_EXBUS +#define PIOS_INCLUDE_IBUS #define PIOS_INCLUDE_GCSRCVR #define PIOS_INCLUDE_OPLINKRCVR #define PIOS_INCLUDE_OPENLRS_RCVR diff --git a/flight/targets/boards/revolution/firmware/pios_board.c b/flight/targets/boards/revolution/firmware/pios_board.c index f491a1e3f..142a7c198 100644 --- a/flight/targets/boards/revolution/firmware/pios_board.c +++ b/flight/targets/boards/revolution/firmware/pios_board.c @@ -586,6 +586,28 @@ void PIOS_Board_Init(void) #endif /* PIOS_INCLUDE_SRXL */ break; + case HWSETTINGS_RM_FLEXIPORT_IBUS: +#if defined(PIOS_INCLUDE_IBUS) + { + uint32_t pios_usart_ibus_id; + if (PIOS_USART_Init(&pios_usart_ibus_id, &pios_usart_ibus_flexi_cfg)) { + PIOS_Assert(0); + } + + uint32_t pios_ibus_id; + if (PIOS_IBUS_Init(&pios_ibus_id, &pios_usart_com_driver, pios_usart_ibus_id)) { + PIOS_Assert(0); + } + + uint32_t pios_ibus_rcvr_id; + if (PIOS_RCVR_Init(&pios_ibus_rcvr_id, &pios_ibus_rcvr_driver, pios_ibus_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_IBUS] = pios_ibus_rcvr_id; + } +#endif /* PIOS_INCLUDE_IBUS */ + break; + case HWSETTINGS_RM_FLEXIPORT_HOTTSUMD: case HWSETTINGS_RM_FLEXIPORT_HOTTSUMH: #if defined(PIOS_INCLUDE_HOTT) diff --git a/flight/targets/boards/revonano/board_hw_defs.c b/flight/targets/boards/revonano/board_hw_defs.c index 7c651de48..c17c7539c 100644 --- a/flight/targets/boards/revonano/board_hw_defs.c +++ b/flight/targets/boards/revonano/board_hw_defs.c @@ -634,6 +634,55 @@ static const struct pios_usart_cfg pios_usart_srxl_flexi_cfg = { #endif /* PIOS_INCLUDE_SRXL */ +#if defined(PIOS_INCLUDE_IBUS) +/* + * IBUS USART + */ +#include + +static const struct pios_usart_cfg pios_usart_ibus_flexi_cfg = { + .regs = FLEXI_USART_REGS, + .remap = FLEXI_USART_REMAP, + .init = { + .USART_BaudRate = 115200, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = FLEXI_USART_IRQ, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = FLEXI_USART_RX_GPIO, + .init = { + .GPIO_Pin = FLEXI_USART_RX_PIN, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + .tx = { + .gpio = FLEXI_USART_TX_GPIO, + .init = { + .GPIO_Pin = FLEXI_USART_TX_PIN, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, +}; + +#endif /* PIOS_INCLUDE_IBUS */ + #if defined(PIOS_INCLUDE_EXBUS) /* * EXBUS USART @@ -681,8 +730,8 @@ static const struct pios_usart_cfg pios_usart_exbus_flexi_cfg = { }, }; - #endif /* PIOS_INCLUDE_EXBUS */ + /* * HK OSD */ diff --git a/flight/targets/boards/revonano/firmware/pios_board.c b/flight/targets/boards/revonano/firmware/pios_board.c index 9e8e6accf..c09a117b3 100644 --- a/flight/targets/boards/revonano/firmware/pios_board.c +++ b/flight/targets/boards/revonano/firmware/pios_board.c @@ -733,7 +733,29 @@ void PIOS_Board_Init(void) } pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SRXL] = pios_srxl_rcvr_id; } -#endif +#endif /* PIOS_INCLUDE_SRXL */ + break; + + case HWSETTINGS_RM_FLEXIPORT_IBUS: +#if defined(PIOS_INCLUDE_IBUS) + { + uint32_t pios_usart_ibus_id; + if (PIOS_USART_Init(&pios_usart_ibus_id, &pios_usart_ibus_flexi_cfg)) { + PIOS_Assert(0); + } + + uint32_t pios_ibus_id; + if (PIOS_IBUS_Init(&pios_ibus_id, &pios_usart_com_driver, pios_usart_ibus_id)) { + PIOS_Assert(0); + } + + uint32_t pios_ibus_rcvr_id; + if (PIOS_RCVR_Init(&pios_ibus_rcvr_id, &pios_ibus_rcvr_driver, pios_ibus_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_IBUS] = pios_ibus_rcvr_id; + } +#endif /* PIOS_INCLUDE_IBUS */ break; case HWSETTINGS_RM_FLEXIPORT_HOTTSUMD: diff --git a/flight/targets/boards/sparky2/board_hw_defs.c b/flight/targets/boards/sparky2/board_hw_defs.c index 7e550cdf7..3fb99a725 100644 --- a/flight/targets/boards/sparky2/board_hw_defs.c +++ b/flight/targets/boards/sparky2/board_hw_defs.c @@ -838,6 +838,86 @@ static const struct pios_usart_cfg pios_usart_srxl_rcvr_cfg = { #endif /* PIOS_INCLUDE_SRXL */ +#if defined(PIOS_INCLUDE_IBUS) +/* + * IBUS USART + */ +#include + +static const struct pios_usart_cfg pios_usart_ibus_flexi_cfg = { + .regs = USART3, + .remap = GPIO_AF_USART3, + .init = { + .USART_BaudRate = 115200, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = USART3_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_11, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, + .tx = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, +}; + +static const struct pios_usart_cfg pios_usart_ibus_rcvr_cfg = { + .regs = USART6, + .remap = GPIO_AF_USART6, + .init = { + .USART_BaudRate = 115200, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = USART6_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_7, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + }, +}; + +#endif /* PIOS_INCLUDE_IBUS */ + // these were copied from Revo support // they might need to be further modified for Sparky2 support #if defined(PIOS_INCLUDE_HOTT) diff --git a/flight/targets/boards/sparky2/firmware/inc/pios_config.h b/flight/targets/boards/sparky2/firmware/inc/pios_config.h index 5a3b39372..e823a82a1 100644 --- a/flight/targets/boards/sparky2/firmware/inc/pios_config.h +++ b/flight/targets/boards/sparky2/firmware/inc/pios_config.h @@ -111,6 +111,7 @@ #define PIOS_INCLUDE_SRXL #define PIOS_INCLUDE_HOTT #define PIOS_INCLUDE_EXBUS +#define PIOS_INCLUDE_IBUS #define PIOS_INCLUDE_GCSRCVR #define PIOS_INCLUDE_OPLINKRCVR #define PIOS_INCLUDE_OPENLRS_RCVR diff --git a/flight/targets/boards/sparky2/firmware/pios_board.c b/flight/targets/boards/sparky2/firmware/pios_board.c index 27446ee6b..f697c156e 100644 --- a/flight/targets/boards/sparky2/firmware/pios_board.c +++ b/flight/targets/boards/sparky2/firmware/pios_board.c @@ -327,6 +327,27 @@ static void PIOS_Board_configure_srxl(const struct pios_usart_cfg *usart_cfg) pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SRXL] = pios_srxl_rcvr_id; } +static void PIOS_Board_configure_ibus(const struct pios_usart_cfg *usart_cfg) +{ + uint32_t pios_usart_ibus_id; + + if (PIOS_USART_Init(&pios_usart_ibus_id, usart_cfg)) { + PIOS_Assert(0); + } + + uint32_t pios_ibus_id; + if (PIOS_IBUS_Init(&pios_ibus_id, &pios_usart_com_driver, pios_usart_ibus_id)) { + PIOS_Assert(0); + } + + uint32_t pios_ibus_rcvr_id; + if (PIOS_RCVR_Init(&pios_ibus_rcvr_id, &pios_ibus_rcvr_driver, pios_ibus_id)) { + PIOS_Assert(0); + } + + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_IBUS] = pios_ibus_rcvr_id; +} + static void PIOS_Board_configure_exbus(const struct pios_usart_cfg *usart_cfg) { @@ -582,6 +603,12 @@ void PIOS_Board_Init(void) #endif /* PIOS_INCLUDE_SRXL */ break; + case HWSETTINGS_SPK2_FLEXIPORT_IBUS: +#if defined(PIOS_INCLUDE_IBUS) + PIOS_Board_configure_ibus(&pios_usart_ibus_flexi_cfg); +#endif /* PIOS_INCLUDE_IBUS */ + break; + case HWSETTINGS_SPK2_FLEXIPORT_HOTTSUMD: case HWSETTINGS_SPK2_FLEXIPORT_HOTTSUMH: #if defined(PIOS_INCLUDE_HOTT) @@ -926,7 +953,7 @@ void PIOS_Board_Init(void) // Configure the receiver port // Sparky2 receiver input on PC7 TIM8 CH2 - // include PPM,S.Bus,DSM,SRXL,EX.Bus,HoTT SUMD,HoTT SUMH + // include PPM,S.Bus,DSM,SRXL,IBus,EX.Bus,HoTT SUMD,HoTT SUMH uint8_t hwsettings_rcvrport; HwSettingsSPK2_RcvrPortGet(&hwsettings_rcvrport); @@ -962,6 +989,11 @@ void PIOS_Board_Init(void) PIOS_Board_configure_srxl(&pios_usart_srxl_rcvr_cfg); #endif /* PIOS_INCLUDE_SRXL */ break; + case HWSETTINGS_SPK2_RCVRPORT_IBUS: +#if defined(PIOS_INCLUDE_IBUS) + PIOS_Board_configure_ibus(&pios_usart_ibus_rcvr_cfg); +#endif /* PIOS_INCLUDE_IBUS */ + break; case HWSETTINGS_SPK2_RCVRPORT_HOTTSUMD: case HWSETTINGS_SPK2_RCVRPORT_HOTTSUMH: #if defined(PIOS_INCLUDE_HOTT) diff --git a/ground/gcs/src/plugins/config/inputchannelform.cpp b/ground/gcs/src/plugins/config/inputchannelform.cpp index 5efbf4a9d..4b8ef15d0 100644 --- a/ground/gcs/src/plugins/config/inputchannelform.cpp +++ b/ground/gcs/src/plugins/config/inputchannelform.cpp @@ -146,6 +146,9 @@ void InputChannelForm::groupUpdated() case ManualControlSettings::CHANNELGROUPS_OPLINK: count = 8; // Need to make this 6 for CC break; + case ManualControlSettings::CHANNELGROUPS_IBUS: + count = 10; + break; case ManualControlSettings::CHANNELGROUPS_DSMMAINPORT: case ManualControlSettings::CHANNELGROUPS_DSMFLEXIPORT: case ManualControlSettings::CHANNELGROUPS_DSMRCVRPORT: diff --git a/shared/uavobjectdefinition/hwsettings.xml b/shared/uavobjectdefinition/hwsettings.xml index bbbbd5200..1eeaa0c48 100644 --- a/shared/uavobjectdefinition/hwsettings.xml +++ b/shared/uavobjectdefinition/hwsettings.xml @@ -3,7 +3,7 @@ Selection of optional hardware configurations. - + @@ -15,11 +15,11 @@ defaultvalue="PWM" limits="%0905NE:PPM+PWM:PPM+Telemetry:Telemetry:ComBridge:MSP:MAVLink;"/> - + - + - + diff --git a/shared/uavobjectdefinition/manualcontrolsettings.xml b/shared/uavobjectdefinition/manualcontrolsettings.xml index 9d9c6bdde..ef1cb93e4 100644 --- a/shared/uavobjectdefinition/manualcontrolsettings.xml +++ b/shared/uavobjectdefinition/manualcontrolsettings.xml @@ -3,7 +3,7 @@ Settings to indicate how to decode receiver input by @ref ManualControlModule. + options="PWM,PPM,DSM (MainPort),DSM (FlexiPort),DSM (RcvrPort),S.Bus,EX.Bus,HoTT,SRXL,IBus,GCS,OPLink,OpenLRS,None" defaultvalue="None"/> Monitors which receiver channels have been active within the last second. From 848638d6e77b60c62fa3b08cb0d014782a728968 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Wed, 3 Aug 2016 19:02:32 +0200 Subject: [PATCH 02/20] LP-298 Add IBus input to wizard --- .../plugins/setupwizard/connectiondiagram.cpp | 3 + .../setupwizard/pages/airspeedpage.cpp | 1 + .../src/plugins/setupwizard/pages/gpspage.cpp | 1 + .../plugins/setupwizard/pages/inputpage.cpp | 11 + .../plugins/setupwizard/pages/inputpage.ui | 55 +- .../setupwizard/resources/bttn-ibus-down.png | Bin 0 -> 3192 bytes .../setupwizard/resources/bttn-ibus-up.png | Bin 0 -> 3792 bytes .../resources/connection-diagrams.svg | 478 +++++++++++++++++- .../src/plugins/setupwizard/setupwizard.cpp | 3 + .../vehicleconfigurationhelper.cpp | 13 + .../setupwizard/vehicleconfigurationsource.h | 2 +- .../plugins/setupwizard/wizardResources.qrc | 2 + 12 files changed, 558 insertions(+), 11 deletions(-) create mode 100644 ground/gcs/src/plugins/setupwizard/resources/bttn-ibus-down.png create mode 100644 ground/gcs/src/plugins/setupwizard/resources/bttn-ibus-up.png diff --git a/ground/gcs/src/plugins/setupwizard/connectiondiagram.cpp b/ground/gcs/src/plugins/setupwizard/connectiondiagram.cpp index a47088e35..5ea7fea46 100644 --- a/ground/gcs/src/plugins/setupwizard/connectiondiagram.cpp +++ b/ground/gcs/src/plugins/setupwizard/connectiondiagram.cpp @@ -213,6 +213,9 @@ void ConnectionDiagram::setupGraphicsScene() case VehicleConfigurationSource::INPUT_EXBUS: elementsToShow << QString("%1exbus").arg(prefix); break; + case VehicleConfigurationSource::INPUT_IBUS: + elementsToShow << QString("%1ibus").arg(prefix); + break; default: break; } diff --git a/ground/gcs/src/plugins/setupwizard/pages/airspeedpage.cpp b/ground/gcs/src/plugins/setupwizard/pages/airspeedpage.cpp index d89e370ba..8182e2bd4 100644 --- a/ground/gcs/src/plugins/setupwizard/pages/airspeedpage.cpp +++ b/ground/gcs/src/plugins/setupwizard/pages/airspeedpage.cpp @@ -46,6 +46,7 @@ void AirSpeedPage::initializePage(VehicleConfigurationSource *settings) settings->getInputType() == VehicleConfigurationSource::INPUT_DSM || settings->getInputType() == VehicleConfigurationSource::INPUT_SRXL || settings->getInputType() == VehicleConfigurationSource::INPUT_HOTT_SUMD || + settings->getInputType() == VehicleConfigurationSource::INPUT_IBUS || settings->getInputType() == VehicleConfigurationSource::INPUT_EXBUS)) || settings->getGpsType() == VehicleConfigurationSource::GPS_UBX_FLEXI_I2CMAG) { // Disable non estimated sensors if ports are taken by receivers or I2C Mag diff --git a/ground/gcs/src/plugins/setupwizard/pages/gpspage.cpp b/ground/gcs/src/plugins/setupwizard/pages/gpspage.cpp index 3f6c4295b..2cba4670b 100644 --- a/ground/gcs/src/plugins/setupwizard/pages/gpspage.cpp +++ b/ground/gcs/src/plugins/setupwizard/pages/gpspage.cpp @@ -46,6 +46,7 @@ void GpsPage::initializePage(VehicleConfigurationSource *settings) settings->getInputType() == VehicleConfigurationSource::INPUT_DSM || settings->getInputType() == VehicleConfigurationSource::INPUT_SRXL || settings->getInputType() == VehicleConfigurationSource::INPUT_HOTT_SUMD || + settings->getInputType() == VehicleConfigurationSource::INPUT_IBUS || settings->getInputType() == VehicleConfigurationSource::INPUT_EXBUS)) { // Disable GPS+I2C Mag setItemDisabled(VehicleConfigurationSource::GPS_UBX_FLEXI_I2CMAG, true); diff --git a/ground/gcs/src/plugins/setupwizard/pages/inputpage.cpp b/ground/gcs/src/plugins/setupwizard/pages/inputpage.cpp index 298236190..87354fc14 100644 --- a/ground/gcs/src/plugins/setupwizard/pages/inputpage.cpp +++ b/ground/gcs/src/plugins/setupwizard/pages/inputpage.cpp @@ -69,6 +69,8 @@ bool InputPage::validatePage() getWizard()->setInputType(SetupWizard::INPUT_HOTT_SUMD); } else if (ui->jetiButton->isChecked()) { getWizard()->setInputType(SetupWizard::INPUT_EXBUS); + } else if (ui->flyskyButton->isChecked()) { + getWizard()->setInputType(SetupWizard::INPUT_IBUS); } else if (ui->spectrumButton->isChecked()) { getWizard()->setInputType(SetupWizard::INPUT_DSM); } else if (ui->multiplexButton->isChecked()) { @@ -112,6 +114,9 @@ bool InputPage::restartNeeded(VehicleConfigurationSource::INPUT_TYPE selectedTyp case VehicleConfigurationSource::INPUT_EXBUS: return data.CC_FlexiPort != HwSettings::CC_FLEXIPORT_EXBUS; + case VehicleConfigurationSource::INPUT_IBUS: + return data.CC_FlexiPort != HwSettings::CC_FLEXIPORT_IBUS; + case VehicleConfigurationSource::INPUT_DSM: // TODO: Handle all of the DSM types ?? Which is most common? return data.CC_MainPort != HwSettings::CC_MAINPORT_DSM; @@ -140,6 +145,9 @@ bool InputPage::restartNeeded(VehicleConfigurationSource::INPUT_TYPE selectedTyp case VehicleConfigurationSource::INPUT_EXBUS: return data.RM_FlexiPort != HwSettings::RM_FLEXIPORT_EXBUS; + case VehicleConfigurationSource::INPUT_IBUS: + return data.RM_FlexiPort != HwSettings::RM_FLEXIPORT_IBUS; + case VehicleConfigurationSource::INPUT_SRXL: return data.RM_FlexiPort != HwSettings::RM_FLEXIPORT_SRXL; @@ -173,6 +181,9 @@ bool InputPage::restartNeeded(VehicleConfigurationSource::INPUT_TYPE selectedTyp case VehicleConfigurationSource::INPUT_EXBUS: return data.SPK2_RcvrPort != HwSettings::SPK2_RCVRPORT_EXBUS; + case VehicleConfigurationSource::INPUT_IBUS: + return data.SPK2_RcvrPort != HwSettings::SPK2_RCVRPORT_IBUS; + default: return true; } break; diff --git a/ground/gcs/src/plugins/setupwizard/pages/inputpage.ui b/ground/gcs/src/plugins/setupwizard/pages/inputpage.ui index 9d17c4f55..eb6147641 100644 --- a/ground/gcs/src/plugins/setupwizard/pages/inputpage.ui +++ b/ground/gcs/src/plugins/setupwizard/pages/inputpage.ui @@ -139,13 +139,6 @@ p, li { white-space: pre-wrap; } - - - - - - 2 - @@ -187,6 +180,13 @@ p, li { white-space: pre-wrap; } + + + + + + 2 + @@ -351,6 +351,47 @@ p, li { white-space: pre-wrap; } + + + + + 10 + + + + FlySky IBus + + + QToolButton { border: none } + + + IBus + + + + :/setupwizard/resources/bttn-ibus-up.png + :/setupwizard/resources/bttn-ibus-down.png:/setupwizard/resources/bttn-ibus-up.png + + + + 100 + 100 + + + + true + + + true + + + Qt::ToolButtonTextUnderIcon + + + true + + + diff --git a/ground/gcs/src/plugins/setupwizard/resources/bttn-ibus-down.png b/ground/gcs/src/plugins/setupwizard/resources/bttn-ibus-down.png new file mode 100644 index 0000000000000000000000000000000000000000..762b30bd7ec8fc2350259abcbc2183a0cb0634cd GIT binary patch literal 3192 zcmV-;42ScHP)ay@;P;glXl-f`P zl}AOTFNlxDXPR!G1g?%-6OfGZENPfwu0#PT`^qVMyXiKUruq}K@67{U%QUDyuJu+Ng#!EB2QQd z%R=Y@Y)hluZ}q5c%~}QegVHeFQ5Y@{y36fEqT#C67HSQeI$ubAoL`Sj2|w?5OK&DU z`8;K`#}jka70qv@r;c!SjLnJ_^EsS*jMtaHOU|hxT3_9@!BeS3B85N~Ho|ry?`(GS z2P%wuw}IUTkCUc58pC~V6zaNxrWp<1?&-S5lwS_w{-5;???7QuF;kwI!`FvPY1RI^ z$VXkEg5unL{N~$N*f_;C;F@awpEE8@M8taIk@F5 ztzH6e96CXoo@fkL6o$)-Q7w(0*NJIBhV|>l@5T=$+Ur!FW!ub6dxLk@enD)fo6vM4 zLQ$7XYwa}iXFWl`TY6R{I4OB=!)}&*^aX*S9RYixPE06$+ExHNScx61!19-KVAC?K zUMW=5Lv5bnaw5+(Ln*Ynz=mh@ms#ZG7c*zdT_nc0#WW25@Z>~#CwC)t-g11`-h}Ci zZm{jy!Ac4bf6YBZ`!M5)7l`pih2J}NvX~d&*u>uN@&FCpFe4O!0vXCW&TzsNN~dQ1 z$AQTsrb^S}!*EAox;^No$B}6`z0gP#6Yb%-2}4Qg*(v9AEm?T`E zGD|l-7@-uZ8OFH-`71Qu-SzD;zRxWnrDsRnE(5Q}!{`wMDLb9d7u$E>Z5@xMU;6i{ zD9$H%B9pn($Mf5X_u=(;!tZTL|DNd!KPBr};T4|Il+MhI6i8_!Z5v_RNIS@hLpx^I zF9Od?w2e32vTaW`lmGZJImb^sN1m?p^wbBL|Li!<!TOc2 zGIH4M;rEJ5D|l|nMrJSD#F=t`<4;dtVpTV*X^z9ki+FhMYCiueJN(*RLk95SlG#L+ z9ipNrzs7Yd&lGSbdj~TgxtllBo+CakHvHb_dvkbj_6Pjq%dBQMi_`4psmdw?{C?5j zS-vI%5o#E_cJ9dPx8~97S|~d9ZS{#pq_8=CD+}g4P3u-ZTE+NSHh%_bOW!4J z>AMKwNc4K#JoD&p82_u$=z3LN`Xc=+rp->{Xx@psCpq23+bWi}9lGO=Zquj&Yt6Jh zfBKj-Jw8lNXgbaGgeJ6&%kISZOABbPonYFO2k3iqGQMbU^T`6`m89?4$1988;iQPi z6Vt8%CbUCmB5Vs``LTn3EWb01_-6frdJZEZNYYgntKNK>!2|joB z^GLeNYSi!2Xac7{JQkPBq&eeuyO{p)*dM0Ao;N1Z5@_uGXf%PQX|@P~jlCZ&|8#c? zM+sB{6-uB&2~+|VN}xgsR49QzESltWNLfVyUzD4Hlb4+L-qyvF!mn>#JgLSq4jw*5 z+Fw8CK=w&ora`w(aXk8q6uNb4e@W{rftP_V%6*=+x-xs|CXSpaX5rJLuq?sje_F@P zB^!C~#rsqQHWeoQ*D4O=oaD_v+)J0lc6^^(!1xzF*xjZ{udeNDJP7{$ z$!?aePUpViz1aP2UXA4~P5pP(2G*B>lb3{->fAdd8Gz4r9&-NfaQ==N)SUlfp}N?&#BnwynHuNyYy=Zw#U<7cx z48{!XPJUq-D?j~;6Q|1{vJSM*_!lo)*myl2OhV<$N$W{ zr1F%&2ry<~4-8%7jkOu!=Kv4RdY^%lmyoePmy%NFcb;)=&b_|xsr!Gz?Y*w!NPaQ9 z4jiquJS8wf#I^M?=$6jdLUQx<*M!sItcgRox!X0QF8Vu9rmdrAQUWt43^{N8q5Zl5 zuxd+Yt>vj+Xg%A$+FlO?ElSG#96ecr228xWZ}>Aw9on(rsZkd#_x9e`T~c{UU<4TX z#M{_Ha80|`JUebMH+8+bNtLGrUWCsUKGdYkQ*EF^2~+|VN}xgsR5a&aX!S|#vtzak zoht-r?elPJ_YOSv%K^l;iB=KV+$bsYvpFM+xo`hdMPPGb>*7fWA=vX>9*@so2f$a~ z<<%I$7mDZ;r%PG*zuWopz%fcI{6u?Q^y|@)-;QnCk!-f8!?EhhYPuxWZ4UGKWt-W1 z=r|yGXZBd~3(xRW+Ik90%6Vz&>w=%H>1K5^9~#2&{#}XoR-L>pF7@-u%55qFuN1aj)d-fB z2f~lNZj;J@b1i$u{@e?$8`svyjQ<>hZ4181%IC3H*CHjHDk@U~uXGy-&UwDGBz1@- z^IuLIH*@hu+O>(Ip!nST!c3mKiv8Iq`Qy|Pv}+R`zBk)#y?>;}fmiHkG&HV_YsIMB zZ{(>5s&1n-lCAM*)HCu2a!xXB!6yLZWUQ(2b3eLuG>RrDusS(k*8D&38{&ki z>V+zlK!p;hPy$saCL&zu9-gZ6q9RZUR49Q8B~YORDuD_mP@x1Wl)x56leDFjm5&Sk(- zph*pht|T_7LlLfDDQ%<>NFnLbEzwS|ufThT_s`sQ;QgC)VIzc%CM=|;AplL27rDY- zQI`O8u93Hp!a@k!xn5pa+%vp?=G(8-Q{b38Q&JD-6|7nQ(Ka;8KnrDDO-kn`2O21g z4PmcJps<`piXanzF@!O9rli)k_C;%7O8MfJ9s5%MvTi$>Stsz@0$n%IG()*-&C5?rF4lnVEP)4qZt^ zK~#9!?VWjeROP+LKWCZAWF|}!U`PT1QkIY=ltr#`E0sP`kUrLeh}Wu6r5Z`SUJH~K zcoacF;lbN`UD>g~^C&8cLTg*}k+lV-2!thq1Vfmcg)ESPkZmUCocl*+;$bp@u*??D z_j%suOwOG1p2_d~et*mRo;f1`0?iQGXyQvRy)+>+4s|nKNf2paNPOtxeJdKz#b?r&H6?(q^Tnr{@eFJeY)p1O!1q(=@}-C^{vodIjp$CjpYxYRwrkWC*pjwKO(1qN-}k1%inp zXE8f=f6axO8h$hRApVYgGRfV#hQ*LY&JtdEYYp9#9Q<B>6h*=9c9W2hfGCPXy~5JRKLOChK;!|UAP8}yD59!ri~53%7iK-f)Tf^$vF8s- z?D-?kHrbi};xY~#$`2`Vs;04F(-x*LSV@Ju6M4>hrY~5<^0ga6_Zhr)7ex_45aRUQ z=)#>4$c6e2Y*AgX-KGzfm6bd;ZUh4}`tr&<|3Efds58Z~VCly^^79fN95*KDpP}qb z1^>P5T?#AQ#HIX@n7Bj)O<}^rzu=L3Zlk*TT&T+m-%FnYMV$*39A2zQ4!A2DCvpw#lS!=)Yrm>3l}aRDRnHHJ)Ys2sl?j5lF)qs2a9T%KJRr( z%F1u(_0FDi@$AASto~#V7Dqbvq`sJ~@!UJ2KdYX-p9G6ad3kxbGjM-?S}Bk~3KRq( zWG++>x7*Fx$}_x>JDT-d4)X42hY{s|oI6*-?-s0JM$UMK4;ysd*V(%3E0(YS8=9pX zi9IqgTkUjBurc#jcaWLZmGU#CsHz$k8~9yQ@|F>Lu3ECtK(jItkxrKs7xO@NCK+kn zSh#j4qSTvuvxS$JZ{oo*P9{$H`865${Dm4`TlpSee_Ku`M_(-VBqUP|ciz&QX^)Jg zw#G$SSy@Dth=KT#+nPp;q)%R1SxLW?PAs2&AI~lO45ug}nPT{8Yd$AWl`!+a9>p3P z+wT6p+?U52Yd7JR6G=?XB*vCNe4K^p50Bus%pROMQ--1_kyajxfw;P?0)6f?9PYy( z7cXAKY&NrW=6DvZ-O8RLBBC6_kzyymo%1>`%$Q8i9x0dYqqeS|rGMJMjst~sa`YxX zJ_*Sj%Z~?kXXdZ6aW`C~w6rv&nfH}ksP1zFRG{eRE+fi?28xT76=gjC#9jRQ-l15m zcI?T0sS&#{ZT@n0?>*S&xp_y9@taw%u;=($I`}db$-<&ln|Ywn$)gXAMf8r`#zr@* z-r2~O-N&$X?L~Y-GP2pq(Ei<+J^4-~%}sG}anwwe`oESh_hzuO&~HzkV)Z+p@J+#K z8XBA0J#++7#%#4?>ynDCb1J478@A5fk<2k{`sWGW`}FrHo<=}GGF!05CzFtxMNC|0 zB$F9URoI(%g1aBxN}a2mriNNHt(`GX151odX8+#gOd8LCem@9R78;NrIb1{OaQ?SE z`^p+j_GIExhhUdXT-7)cBxJJ%Nj8H3qHHGC?m#x%i0je|O>F`M1WCpeV?&OyB8ZZ2 z1Rz_iSUdN?Vt2q*)OVT&s^a0~+4IbJX(bE)FquJF1HvXr`5H#T4Z)g?+lWgUKx}+6 zlF5P~UVrHIDbsAVU*Z1|kTtOAtlm7%SGq6iQv;T^|h_fr8nFWQrl0A(>(j%;CL7NN!IZ5)2nAN)mz~ zMm2$gAbS4~AxQmS+4j+GK?7G#Vj^WGCbE?%gsopgfrbJN7z#8Hyeu@BBg|0X_4jQk z(1?Ksj2LL3<0w!P1r${?6d0`vj5hKjJ_|KsV0aaHrM~4zHq5RSQ(EmCnY*%O|H#~x zZJyh=M`xx!bUPVo4m?dNC!AF*`S43l7N2X^`9=)9fw&e!zwqQ;^iE0Ssl}Tx$r5kO z_ysRc8O6l88=^{q*G*s~WBIIcWcEqou@^t&RB1Io=$^>BdH=z&q6!i^Spe{O6!Hrz z+8hKE#|$R-{^7j4C6A%$DQ)(byJ%BH+CXgYNVw7MYF(+X>9KKp^ViNs-`1~rJG^rawG_w3LKa{f_@>Cb{8JZDp%bl=f3*hZgw9!OvVJveuvo}C9yVUi^d953PY z85aOAuHMT2<0ZWO)M)-^+C3aDC}aNH+ghFf#lDj*@$ho}MXINY=rW?M%+a@BmIUlJ z3*8-d6h&p#rhP5P6qUJ{{_0<^*zcD|{;ysA8D&He@Yh!-BZ&fKRW&SHw}bps6%o~6 zL`!uyp+G}{20ESsBV|EXKZ)(D*#fN<0#w)3 zv;SBLZ+x%^*TsgYSKxIo=ti3hP3#oQsN4EswV0T_-Cf8%XLB$E(xtrL*12)c^f7V(rr*6zCrh3ro)O@|x{e)kj8}1881S`pJ+q zjulmq{nV<6ze}z|-j&unIgwj4Q`x-hSi8^3FRWl#Mh{G~#D6~U@68F(g*skXwUvV> z$|5$2=@4avZ?*oJKmHj2NfLSVo}mGcmBhdXS@8BYwtRVln!3jC6C%5n858d?3i(h$ zlD;30an|o2pio=y#ujS^;MUC4fajjOP|w1(I}ilO>XXD9Gwwx}Bpivhb}7ZkLT_LU z1o&rO(f2X2^c+9xn+(AGDWj;YzKA0+?vmq|%^F8mpCo3!`FGBquS1ra9}2Yl&}l<~ zp@Q4fL`8Ki`;V8f^rNp@_AmYDE9O3NCl<5JYwz#j;kyU5B5>ZyFZkUfKVi<}*;p+m z&YiDg&*9U&rRyi^6c{NWwmPPwy7rn2eVdGG``?zWT6H+Y7F$vbVR)YgZ#M3h>d{*(vr|LHLA(e zG?f8qNn!mAVf%vT)JdZewWg>hP}G{3I%)LH`329c{;4dRbsxjh9av1hpT>&{-C;3F z3`=*geD-*<`lsHUS*WV2^hxc?AE%8)io$rPC<-2rC#b({7V(c6QB{@3#^wdoL3ck9 z@FD1m$Iao-R~zYOq|d~dW8;a9ceL7Hf4=gjtwW<~K{qzufvrnVLsHSIz;MiTbOZ$& zGcg@mfuWoW-T%=707g9iCXy)z#nZ^{KRpA`lIYxw3XGbE-T6pz*PkcW)D3t2`J0xw z8yW*c9fMR)W6Rc91-UYe7-$e^AmYmiqkJ&R2m|3PBMb#bZW&=H&`4qo7)gu{z8M*4 zUUM^&nCl?Wv$IJm65jvhTqa&odUr4>dTJ$kg= z3e@~xJDpDQ^70HTh6#Cjc{rWUHu=#jP-}xo4jec@RaF&PSy?z7j*!R1n+;7(O;lD^ zlAoWiC$CKs7O?r07@#u)A%do9b$V{}Z;64(12nhWeNojso7vl9a&vR<>D8;(gBFV= zOB6+mVdkL5yoQE`hJ2^fxnaeM6@LR70k^k#ysbrzJ_1D@fxc$;BU1JwTk=z^fol+) zPEC6E=p#u_oZGvvNk^b6`zJ5D&YEBF{&lL1g=hqYbDeb0PiUQk{*M+>nBl9isGk4ZT`wL+~sBwE)>7&UehVi7xR1<5OuCq2;f2uTs?_e8+nN8 z=Qfo@^$O|rsfymSXh|NGW + + + + @@ -20041,6 +20081,115 @@ + + + Satellite + + + + + + + + + + + + + + + + + + + + + + + + + style="display:inline" + sodipodi:insensitive="true"> getControllerType() == VehicleConfigurationSource::CONTROLLER_SPARKY2) { + data.SPK2_RcvrPort = HwSettings::SPK2_RCVRPORT_IBUS; + } else { + data.RM_FlexiPort = HwSettings::RM_FLEXIPORT_IBUS; + } + break; default: break; } @@ -999,6 +1009,9 @@ void VehicleConfigurationHelper::applyManualControlDefaults() case VehicleConfigurationSource::INPUT_EXBUS: channelType = ManualControlSettings::CHANNELGROUPS_EXBUS; break; + case VehicleConfigurationSource::INPUT_IBUS: + channelType = ManualControlSettings::CHANNELGROUPS_IBUS; + break; default: break; } diff --git a/ground/gcs/src/plugins/setupwizard/vehicleconfigurationsource.h b/ground/gcs/src/plugins/setupwizard/vehicleconfigurationsource.h index 62fbc926f..00e2a88fb 100644 --- a/ground/gcs/src/plugins/setupwizard/vehicleconfigurationsource.h +++ b/ground/gcs/src/plugins/setupwizard/vehicleconfigurationsource.h @@ -66,7 +66,7 @@ public: GROUNDVEHICLE_MOTORCYCLE, GROUNDVEHICLE_CAR, GROUNDVEHICLE_DIFFERENTIAL }; enum ESC_TYPE { ESC_ONESHOT, ESC_SYNCHED, ESC_RAPID, ESC_STANDARD, ESC_UNKNOWN }; enum SERVO_TYPE { SERVO_ANALOG, SERVO_DIGITAL, SERVO_UNKNOWN }; - enum INPUT_TYPE { INPUT_PWM, INPUT_PPM, INPUT_SBUS, INPUT_DSM, INPUT_SRXL, INPUT_HOTT_SUMD, INPUT_EXBUS, INPUT_UNKNOWN }; + enum INPUT_TYPE { INPUT_PWM, INPUT_PPM, INPUT_SBUS, INPUT_DSM, INPUT_SRXL, INPUT_HOTT_SUMD, INPUT_EXBUS, INPUT_IBUS, INPUT_UNKNOWN }; enum AIRSPEED_TYPE { AIRSPEED_ESTIMATE, AIRSPEED_EAGLETREE, AIRSPEED_MS4525, AIRSPEED_DISABLED }; enum GPS_TYPE { GPS_PLATINUM, GPS_NAZA, GPS_UBX_FLEXI_I2CMAG, GPS_UBX, GPS_NMEA, GPS_DISABLED }; enum RADIO_SETTING { RADIO_TELEMETRY, RADIO_DISABLED }; diff --git a/ground/gcs/src/plugins/setupwizard/wizardResources.qrc b/ground/gcs/src/plugins/setupwizard/wizardResources.qrc index 646558f0c..dffe4bac9 100644 --- a/ground/gcs/src/plugins/setupwizard/wizardResources.qrc +++ b/ground/gcs/src/plugins/setupwizard/wizardResources.qrc @@ -60,5 +60,7 @@ resources/bttn-hott-up.png resources/bttn-exbus-down.png resources/bttn-exbus-up.png + resources/bttn-ibus-down.png + resources/bttn-ibus-up.png From e52d2636f0eed043ab4415bd0398794d35f9615b Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Wed, 3 Aug 2016 19:52:34 +0200 Subject: [PATCH 03/20] LP-298 Use PIOS_IBUS_NUM_INPUTS like other inputs --- flight/pios/common/pios_ibus.c | 15 +++++++-------- flight/targets/boards/revolution/pios_board.h | 6 ++++++ flight/targets/boards/revonano/pios_board.h | 6 ++++++ flight/targets/boards/sparky2/pios_board.h | 6 ++++++ 4 files changed, 25 insertions(+), 8 deletions(-) diff --git a/flight/pios/common/pios_ibus.c b/flight/pios/common/pios_ibus.c index 5f3300d53..4ba74fcf2 100644 --- a/flight/pios/common/pios_ibus.c +++ b/flight/pios/common/pios_ibus.c @@ -1,7 +1,8 @@ /** ****************************************************************************** * @file pios_ibus.c - * @author dRonin, http://dRonin.org/, Copyright (C) 2016 + * @author The LibrePilot Project, http://www.librepilot.org Copyright (C) 2016. + * dRonin, http://dRonin.org/, Copyright (C) 2016 * @addtogroup PIOS PIOS Core hardware abstraction layer * @{ * @addtogroup PIOS_IBus PiOS IBus receiver driver @@ -32,10 +33,8 @@ #ifdef PIOS_INCLUDE_IBUS -// private -#define PIOS_IBUS_CHANNELS 10 // 1 sync byte, 1 unknown byte, 10x channels (uint16_t), 8 unknown bytes, 2 crc bytes -#define PIOS_IBUS_BUFLEN (1 + 1 + PIOS_IBUS_CHANNELS * 2 + 8 + 2) +#define PIOS_IBUS_BUFLEN (1 + 1 + PIOS_IBUS_NUM_INPUTS * 2 + 8 + 2) #define PIOS_IBUS_SYNCBYTE 0x20 #define PIOS_IBUS_MAGIC 0x84fd9a39 @@ -48,7 +47,7 @@ struct pios_ibus_dev { int rx_timer; int failsafe_timer; uint16_t checksum; - uint16_t channel_data[PIOS_IBUS_CHANNELS]; + uint16_t channel_data[PIOS_IBUS_NUM_INPUTS]; uint8_t rx_buf[PIOS_IBUS_BUFLEN]; }; @@ -154,7 +153,7 @@ int32_t PIOS_IBUS_Init(uint32_t *ibus_id, const struct pios_com_driver *driver, static int32_t PIOS_IBUS_Read(uint32_t context, uint8_t channel) { - if (channel > PIOS_IBUS_CHANNELS) { + if (channel > PIOS_IBUS_NUM_INPUTS) { return PIOS_RCVR_INVALID; } @@ -168,7 +167,7 @@ static int32_t PIOS_IBUS_Read(uint32_t context, uint8_t channel) static void PIOS_IBUS_SetAllChannels(struct pios_ibus_dev *ibus_dev, uint16_t value) { - for (int i = 0; i < PIOS_IBUS_CHANNELS; i++) { + for (int i = 0; i < PIOS_IBUS_NUM_INPUTS; i++) { ibus_dev->channel_data[i] = value; } } @@ -223,7 +222,7 @@ static void PIOS_IBUS_UnpackFrame(struct pios_ibus_dev *ibus_dev) } uint16_t *chan = (uint16_t *)&ibus_dev->rx_buf[2]; - for (int i = 0; i < PIOS_IBUS_CHANNELS; i++) { + for (int i = 0; i < PIOS_IBUS_NUM_INPUTS; i++) { ibus_dev->channel_data[i] = *chan++; } diff --git a/flight/targets/boards/revolution/pios_board.h b/flight/targets/boards/revolution/pios_board.h index 9d002f5c9..a97fdbd67 100644 --- a/flight/targets/boards/revolution/pios_board.h +++ b/flight/targets/boards/revolution/pios_board.h @@ -287,6 +287,12 @@ extern uint32_t pios_packet_handler; #define PIOS_DSM_MAX_DEVS 2 #define PIOS_DSM_NUM_INPUTS 12 +// ------------------------- +// Receiver FlySky IBus input +// ------------------------- +#define PIOS_IBUS_MAX_DEVS 1 +#define PIOS_IBUS_NUM_INPUTS 10 + // ------------------------- // Servo outputs // ------------------------- diff --git a/flight/targets/boards/revonano/pios_board.h b/flight/targets/boards/revonano/pios_board.h index 32a7ee50c..43c55959c 100644 --- a/flight/targets/boards/revonano/pios_board.h +++ b/flight/targets/boards/revonano/pios_board.h @@ -287,6 +287,12 @@ extern uint32_t pios_packet_handler; #define PIOS_DSM_MAX_DEVS 2 #define PIOS_DSM_NUM_INPUTS 12 +// ------------------------- +// Receiver FlySky IBus input +// ------------------------- +#define PIOS_IBUS_MAX_DEVS 1 +#define PIOS_IBUS_NUM_INPUTS 10 + // ------------------------- // Servo outputs // ------------------------- diff --git a/flight/targets/boards/sparky2/pios_board.h b/flight/targets/boards/sparky2/pios_board.h index 15a86a175..26bbb7e53 100644 --- a/flight/targets/boards/sparky2/pios_board.h +++ b/flight/targets/boards/sparky2/pios_board.h @@ -289,6 +289,12 @@ extern uint32_t pios_packet_handler; #define PIOS_DSM_MAX_DEVS 2 #define PIOS_DSM_NUM_INPUTS 12 +// ------------------------- +// Receiver FlySky IBus input +// ------------------------- +#define PIOS_IBUS_MAX_DEVS 1 +#define PIOS_IBUS_NUM_INPUTS 10 + // ------------------------- // Servo outputs // ------------------------- From 34f55ffbe2fe5f74c86d5f2d7667868e8f4e333f Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Fri, 5 Aug 2016 20:49:34 +0200 Subject: [PATCH 04/20] LP-298 Use PIOS_Board_configure_ibus() for all boards - Missing define for RevoNano --- .../coptercontrol/firmware/pios_board.c | 38 ++++++++++-------- .../boards/revolution/firmware/pios_board.c | 39 +++++++++++-------- .../revonano/firmware/inc/pios_config.h | 1 + .../boards/revonano/firmware/pios_board.c | 39 +++++++++++-------- 4 files changed, 66 insertions(+), 51 deletions(-) diff --git a/flight/targets/boards/coptercontrol/firmware/pios_board.c b/flight/targets/boards/coptercontrol/firmware/pios_board.c index 820211c1d..fb1abb210 100644 --- a/flight/targets/boards/coptercontrol/firmware/pios_board.c +++ b/flight/targets/boards/coptercontrol/firmware/pios_board.c @@ -156,6 +156,26 @@ static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm pios_rcvr_group_map[channelgroup] = pios_dsm_rcvr_id; } +static void PIOS_Board_configure_ibus(const struct pios_usart_cfg *usart_cfg) +{ + uint32_t pios_usart_ibus_id; + + if (PIOS_USART_Init(&pios_usart_ibus_id, usart_cfg)) { + PIOS_Assert(0); + } + + uint32_t pios_ibus_id; + if (PIOS_IBUS_Init(&pios_ibus_id, &pios_usart_com_driver, pios_usart_ibus_id)) { + PIOS_Assert(0); + } + + uint32_t pios_ibus_rcvr_id; + if (PIOS_RCVR_Init(&pios_ibus_rcvr_id, &pios_ibus_rcvr_driver, pios_ibus_id)) { + PIOS_Assert(0); + } + + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_IBUS] = pios_ibus_rcvr_id; +} /** * Configuration for MPU6000 chip @@ -671,23 +691,7 @@ void PIOS_Board_Init(void) case HWSETTINGS_CC_FLEXIPORT_IBUS: #if defined(PIOS_INCLUDE_IBUS) - { - uint32_t pios_usart_ibus_id; - if (PIOS_USART_Init(&pios_usart_ibus_id, &pios_usart_ibus_flexi_cfg)) { - PIOS_Assert(0); - } - - uint32_t pios_ibus_id; - if (PIOS_IBUS_Init(&pios_ibus_id, &pios_usart_com_driver, pios_usart_ibus_id)) { - PIOS_Assert(0); - } - - uint32_t pios_ibus_rcvr_id; - if (PIOS_RCVR_Init(&pios_ibus_rcvr_id, &pios_ibus_rcvr_driver, pios_ibus_id)) { - PIOS_Assert(0); - } - pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_IBUS] = pios_ibus_rcvr_id; - } + PIOS_Board_configure_ibus(&pios_usart_ibus_flexi_cfg); #endif /* PIOS_INCLUDE_IBUS */ break; diff --git a/flight/targets/boards/revolution/firmware/pios_board.c b/flight/targets/boards/revolution/firmware/pios_board.c index 142a7c198..19cdec019 100644 --- a/flight/targets/boards/revolution/firmware/pios_board.c +++ b/flight/targets/boards/revolution/firmware/pios_board.c @@ -341,6 +341,27 @@ static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm pios_rcvr_group_map[channelgroup] = pios_dsm_rcvr_id; } +static void PIOS_Board_configure_ibus(const struct pios_usart_cfg *usart_cfg) +{ + uint32_t pios_usart_ibus_id; + + if (PIOS_USART_Init(&pios_usart_ibus_id, usart_cfg)) { + PIOS_Assert(0); + } + + uint32_t pios_ibus_id; + if (PIOS_IBUS_Init(&pios_ibus_id, &pios_usart_com_driver, pios_usart_ibus_id)) { + PIOS_Assert(0); + } + + uint32_t pios_ibus_rcvr_id; + if (PIOS_RCVR_Init(&pios_ibus_rcvr_id, &pios_ibus_rcvr_driver, pios_ibus_id)) { + PIOS_Assert(0); + } + + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_IBUS] = pios_ibus_rcvr_id; +} + static void PIOS_Board_configure_pwm(const struct pios_pwm_cfg *pwm_cfg) { /* Set up the receiver port. Later this should be optional */ @@ -588,23 +609,7 @@ void PIOS_Board_Init(void) case HWSETTINGS_RM_FLEXIPORT_IBUS: #if defined(PIOS_INCLUDE_IBUS) - { - uint32_t pios_usart_ibus_id; - if (PIOS_USART_Init(&pios_usart_ibus_id, &pios_usart_ibus_flexi_cfg)) { - PIOS_Assert(0); - } - - uint32_t pios_ibus_id; - if (PIOS_IBUS_Init(&pios_ibus_id, &pios_usart_com_driver, pios_usart_ibus_id)) { - PIOS_Assert(0); - } - - uint32_t pios_ibus_rcvr_id; - if (PIOS_RCVR_Init(&pios_ibus_rcvr_id, &pios_ibus_rcvr_driver, pios_ibus_id)) { - PIOS_Assert(0); - } - pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_IBUS] = pios_ibus_rcvr_id; - } + PIOS_Board_configure_ibus(&pios_usart_ibus_flexi_cfg); #endif /* PIOS_INCLUDE_IBUS */ break; diff --git a/flight/targets/boards/revonano/firmware/inc/pios_config.h b/flight/targets/boards/revonano/firmware/inc/pios_config.h index 984b77959..49a64f09a 100644 --- a/flight/targets/boards/revonano/firmware/inc/pios_config.h +++ b/flight/targets/boards/revonano/firmware/inc/pios_config.h @@ -111,6 +111,7 @@ #define PIOS_INCLUDE_SRXL #define PIOS_INCLUDE_HOTT #define PIOS_INCLUDE_EXBUS +#define PIOS_INCLUDE_IBUS #define PIOS_INCLUDE_GCSRCVR // #define PIOS_INCLUDE_OPLINKRCVR diff --git a/flight/targets/boards/revonano/firmware/pios_board.c b/flight/targets/boards/revonano/firmware/pios_board.c index c09a117b3..9afeab413 100644 --- a/flight/targets/boards/revonano/firmware/pios_board.c +++ b/flight/targets/boards/revonano/firmware/pios_board.c @@ -288,6 +288,27 @@ static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm pios_rcvr_group_map[channelgroup] = pios_dsm_rcvr_id; } +static void PIOS_Board_configure_ibus(const struct pios_usart_cfg *usart_cfg) +{ + uint32_t pios_usart_ibus_id; + + if (PIOS_USART_Init(&pios_usart_ibus_id, usart_cfg)) { + PIOS_Assert(0); + } + + uint32_t pios_ibus_id; + if (PIOS_IBUS_Init(&pios_ibus_id, &pios_usart_com_driver, pios_usart_ibus_id)) { + PIOS_Assert(0); + } + + uint32_t pios_ibus_rcvr_id; + if (PIOS_RCVR_Init(&pios_ibus_rcvr_id, &pios_ibus_rcvr_driver, pios_ibus_id)) { + PIOS_Assert(0); + } + + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_IBUS] = pios_ibus_rcvr_id; +} + static void PIOS_Board_configure_pwm(const struct pios_pwm_cfg *pwm_cfg) { /* Set up the receiver port. Later this should be optional */ @@ -738,23 +759,7 @@ void PIOS_Board_Init(void) case HWSETTINGS_RM_FLEXIPORT_IBUS: #if defined(PIOS_INCLUDE_IBUS) - { - uint32_t pios_usart_ibus_id; - if (PIOS_USART_Init(&pios_usart_ibus_id, &pios_usart_ibus_flexi_cfg)) { - PIOS_Assert(0); - } - - uint32_t pios_ibus_id; - if (PIOS_IBUS_Init(&pios_ibus_id, &pios_usart_com_driver, pios_usart_ibus_id)) { - PIOS_Assert(0); - } - - uint32_t pios_ibus_rcvr_id; - if (PIOS_RCVR_Init(&pios_ibus_rcvr_id, &pios_ibus_rcvr_driver, pios_ibus_id)) { - PIOS_Assert(0); - } - pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_IBUS] = pios_ibus_rcvr_id; - } + PIOS_Board_configure_ibus(&pios_usart_ibus_flexi_cfg); #endif /* PIOS_INCLUDE_IBUS */ break; From 73c96be4b725d564af1b67e438990b1ce3143d7c Mon Sep 17 00:00:00 2001 From: Vladimir Zidar Date: Wed, 22 Jun 2016 22:27:37 +0200 Subject: [PATCH 05/20] LP-239 Use Revo HW widget for DiscoveryF4 --- ground/gcs/src/plugins/config/configgadgetwidget.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/gcs/src/plugins/config/configgadgetwidget.cpp b/ground/gcs/src/plugins/config/configgadgetwidget.cpp index a5f6b02fa..6de6e0631 100644 --- a/ground/gcs/src/plugins/config/configgadgetwidget.cpp +++ b/ground/gcs/src/plugins/config/configgadgetwidget.cpp @@ -196,7 +196,7 @@ void ConfigGadgetWidget::onAutopilotConnect() // Revolution family QWidget *qwd = new ConfigRevoWidget(this); stackWidget->replaceTab(ConfigGadgetWidget::sensors, qwd); - if (board == 0x0903) { + if (board == 0x0903 || board == 0x0904) { qwd = new ConfigRevoHWWidget(this); } else if (board == 0x0905) { qwd = new ConfigRevoNanoHWWidget(this); From 51151e629000006f296691bcd9b3318970538f92 Mon Sep 17 00:00:00 2001 From: Vladimir Zidar Date: Sat, 6 Aug 2016 03:15:15 +0200 Subject: [PATCH 06/20] LP-239 This commit adds missing com protocols (GPS) to Revo Flexi IO (rcvrport) including proper GCS handling --- .../boards/discoveryf4bare/board_hw_defs.c | 58 ++++++ .../discoveryf4bare/firmware/pios_board.c | 42 ++++- .../boards/revolution/firmware/pios_board.c | 32 +++- .../src/plugins/config/configrevohwwidget.cpp | 168 +++++++++++++++++- .../src/plugins/config/configrevohwwidget.ui | 22 +++ shared/uavobjectdefinition/hwsettings.xml | 4 +- 6 files changed, 310 insertions(+), 16 deletions(-) diff --git a/flight/targets/boards/discoveryf4bare/board_hw_defs.c b/flight/targets/boards/discoveryf4bare/board_hw_defs.c index 345864847..c4b87270f 100644 --- a/flight/targets/boards/discoveryf4bare/board_hw_defs.c +++ b/flight/targets/boards/discoveryf4bare/board_hw_defs.c @@ -973,6 +973,64 @@ static const struct pios_usart_cfg pios_usart_hkosd_flexi_cfg = { }, }; +static const struct pios_usart_cfg pios_usart_rcvrport_cfg = { + .regs = USART6, + .remap = GPIO_AF_USART6, + .init = { + .USART_BaudRate = 57600, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = USART6_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + + .dtr = { + // FlexIO pin 9 + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_8, + .GPIO_Speed = GPIO_Speed_25MHz, + .GPIO_Mode = GPIO_Mode_OUT, + .GPIO_OType = GPIO_OType_PP, + }, + }, + + .tx = { + // * 7: PC6 = TIM8 CH1, USART6 TX + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_6, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource6, + }, + + .rx = { + // * 8: PC7 = TIM8 CH2, USART6 RX + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_7, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_UP + }, + .pin_source = GPIO_PinSource7, + } +}; + #if defined(PIOS_INCLUDE_COM) #include diff --git a/flight/targets/boards/discoveryf4bare/firmware/pios_board.c b/flight/targets/boards/discoveryf4bare/firmware/pios_board.c index 50aaccbdc..5d021f6d8 100644 --- a/flight/targets/boards/discoveryf4bare/firmware/pios_board.c +++ b/flight/targets/boards/discoveryf4bare/firmware/pios_board.c @@ -235,7 +235,8 @@ uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE]; #define PIOS_COM_TELEM_RF_RX_BUF_LEN 512 #define PIOS_COM_TELEM_RF_TX_BUF_LEN 512 -#define PIOS_COM_GPS_RX_BUF_LEN 32 +#define PIOS_COM_GPS_RX_BUF_LEN 128 +#define PIOS_COM_GPS_TX_BUF_LEN 32 #define PIOS_COM_TELEM_USB_RX_BUF_LEN 65 #define PIOS_COM_TELEM_USB_TX_BUF_LEN 65 @@ -626,7 +627,7 @@ void PIOS_Board_Init(void) PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); break; case HWSETTINGS_RM_MAINPORT_GPS: - PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_GPS_RX_BUF_LEN, -1, &pios_usart_com_driver, &pios_com_gps_id); + PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); break; case HWSETTINGS_RM_MAINPORT_SBUS: #if defined(PIOS_INCLUDE_SBUS) @@ -731,7 +732,7 @@ void PIOS_Board_Init(void) #endif /* PIOS_INCLUDE_I2C */ break; case HWSETTINGS_RM_FLEXIPORT_GPS: - PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_GPS_RX_BUF_LEN, -1, &pios_usart_com_driver, &pios_com_gps_id); + PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); break; case HWSETTINGS_RM_FLEXIPORT_DSM: // TODO: Define the various Channelgroup for Revo dsm inputs and handle here @@ -895,6 +896,12 @@ void PIOS_Board_Init(void) case HWSETTINGS_RM_RCVRPORT_PPM: case HWSETTINGS_RM_RCVRPORT_PPMOUTPUTS: case HWSETTINGS_RM_RCVRPORT_PPMPWM: + case HWSETTINGS_RM_RCVRPORT_PPMTELEMETRY: + case HWSETTINGS_RM_RCVRPORT_PPMDEBUGCONSOLE: + case HWSETTINGS_RM_RCVRPORT_PPMCOMBRIDGE: + case HWSETTINGS_RM_RCVRPORT_PPMMSP: + case HWSETTINGS_RM_RCVRPORT_PPMMAVLINK: + case HWSETTINGS_RM_RCVRPORT_PPMGPS: #if defined(PIOS_INCLUDE_PPM) if (hwsettings_rcvrport == HWSETTINGS_RM_RCVRPORT_PPMOUTPUTS) { // configure servo outputs and the remaining 5 inputs as outputs @@ -916,6 +923,35 @@ void PIOS_Board_Init(void) break; } + // Configure rcvrport usart + switch (hwsettings_rcvrport) { + case HWSETTINGS_RM_RCVRPORT_TELEMETRY: + case HWSETTINGS_RM_RCVRPORT_PPMTELEMETRY: + PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); + break; + case HWSETTINGS_RM_RCVRPORT_DEBUGCONSOLE: + case HWSETTINGS_RM_RCVRPORT_PPMDEBUGCONSOLE: +#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) + PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id); +#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ + break; + case HWSETTINGS_RM_RCVRPORT_COMBRIDGE: + case HWSETTINGS_RM_RCVRPORT_PPMCOMBRIDGE: + PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); + break; + case HWSETTINGS_RM_RCVRPORT_MSP: + case HWSETTINGS_RM_RCVRPORT_PPMMSP: + PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_MSP_RX_BUF_LEN, PIOS_COM_MSP_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_msp_id); + break; + case HWSETTINGS_RM_RCVRPORT_MAVLINK: + case HWSETTINGS_RM_RCVRPORT_PPMMAVLINK: + PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id); + break; + case HWSETTINGS_RM_RCVRPORT_GPS: + case HWSETTINGS_RM_RCVRPORT_PPMGPS: + PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); + break; + } #if defined(PIOS_INCLUDE_GCSRCVR) GCSReceiverInitialize(); diff --git a/flight/targets/boards/revolution/firmware/pios_board.c b/flight/targets/boards/revolution/firmware/pios_board.c index f491a1e3f..60145bead 100644 --- a/flight/targets/boards/revolution/firmware/pios_board.c +++ b/flight/targets/boards/revolution/firmware/pios_board.c @@ -985,10 +985,9 @@ void PIOS_Board_Init(void) /* Configure the receiver port*/ uint8_t hwsettings_rcvrport; HwSettingsRM_RcvrPortGet(&hwsettings_rcvrport); - // + + // Configure rcvrport PPM/PWM/OUTPUTS switch (hwsettings_rcvrport) { - case HWSETTINGS_RM_RCVRPORT_DISABLED: - break; case HWSETTINGS_RM_RCVRPORT_PWM: #if defined(PIOS_INCLUDE_PWM) /* Set up the receiver port. Later this should be optional */ @@ -999,6 +998,11 @@ void PIOS_Board_Init(void) case HWSETTINGS_RM_RCVRPORT_PPMOUTPUTS: case HWSETTINGS_RM_RCVRPORT_PPMPWM: case HWSETTINGS_RM_RCVRPORT_PPMTELEMETRY: + case HWSETTINGS_RM_RCVRPORT_PPMDEBUGCONSOLE: + case HWSETTINGS_RM_RCVRPORT_PPMCOMBRIDGE: + case HWSETTINGS_RM_RCVRPORT_PPMMSP: + case HWSETTINGS_RM_RCVRPORT_PPMMAVLINK: + case HWSETTINGS_RM_RCVRPORT_PPMGPS: #if defined(PIOS_INCLUDE_PPM) PIOS_Board_configure_ppm(&pios_ppm_cfg); @@ -1012,28 +1016,42 @@ void PIOS_Board_Init(void) PIOS_Board_configure_pwm(&pios_pwm_ppm_cfg); } - if (hwsettings_rcvrport == HWSETTINGS_RM_RCVRPORT_PPMTELEMETRY) { - PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); - } - break; #endif /* PIOS_INCLUDE_PPM */ case HWSETTINGS_RM_RCVRPORT_OUTPUTS: // configure only the servo outputs pios_servo_cfg = &pios_servo_cfg_out_in; break; + } + + // Configure rcvrport usart + switch (hwsettings_rcvrport) { case HWSETTINGS_RM_RCVRPORT_TELEMETRY: + case HWSETTINGS_RM_RCVRPORT_PPMTELEMETRY: PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); break; + case HWSETTINGS_RM_RCVRPORT_DEBUGCONSOLE: + case HWSETTINGS_RM_RCVRPORT_PPMDEBUGCONSOLE: +#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) + PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id); +#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ + break; case HWSETTINGS_RM_RCVRPORT_COMBRIDGE: + case HWSETTINGS_RM_RCVRPORT_PPMCOMBRIDGE: PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); break; case HWSETTINGS_RM_RCVRPORT_MSP: + case HWSETTINGS_RM_RCVRPORT_PPMMSP: PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_MSP_RX_BUF_LEN, PIOS_COM_MSP_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_msp_id); break; case HWSETTINGS_RM_RCVRPORT_MAVLINK: + case HWSETTINGS_RM_RCVRPORT_PPMMAVLINK: PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id); break; + case HWSETTINGS_RM_RCVRPORT_GPS: + case HWSETTINGS_RM_RCVRPORT_PPMGPS: + PIOS_Board_configure_com(&pios_usart_rcvrport_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); + break; } #if defined(PIOS_INCLUDE_GCSRCVR) diff --git a/ground/gcs/src/plugins/config/configrevohwwidget.cpp b/ground/gcs/src/plugins/config/configrevohwwidget.cpp index 7519c7300..5db232191 100644 --- a/ground/gcs/src/plugins/config/configrevohwwidget.cpp +++ b/ground/gcs/src/plugins/config/configrevohwwidget.cpp @@ -70,11 +70,13 @@ ConfigRevoHWWidget::ConfigRevoHWWidget(QWidget *parent) : ConfigTaskWidget(paren addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbMainComSpeed); addWidgetBinding("HwSettings", "TelemetrySpeed", m_ui->cbRcvrTelemSpeed); + addWidgetBinding("HwSettings", "GPSSpeed", m_ui->cbRcvrGPSSpeed); addWidgetBinding("HwSettings", "ComUsbBridgeSpeed", m_ui->cbRcvrComSpeed); // Add Gps protocol configuration addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbMainGPSProtocol); addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbFlexiGPSProtocol); + addWidgetBinding("GPSSettings", "DataProtocol", m_ui->cbRcvrGPSProtocol); connect(m_ui->cchwHelp, SIGNAL(clicked()), this, SLOT(openHelp())); @@ -158,7 +160,12 @@ void ConfigRevoHWWidget::usbVCPPortChanged(int index) if (!vcpComBridgeEnabled && isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE)) { setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED); } + if (!vcpComBridgeEnabled && isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMCOMBRIDGE)) { + setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM); + } + enableComboBoxOptionItem(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE, vcpComBridgeEnabled); + enableComboBoxOptionItem(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMCOMBRIDGE, vcpComBridgeEnabled); // _DEBUGCONSOLE modes are mutual exclusive if (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DEBUGCONSOLE)) { @@ -168,6 +175,12 @@ void ConfigRevoHWWidget::usbVCPPortChanged(int index) if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DEBUGCONSOLE)) { setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED); } + if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DEBUGCONSOLE)) { + setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED); + } + if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMDEBUGCONSOLE)) { + setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM); + } } // _USBTELEMETRY modes are mutual exclusive @@ -207,8 +220,10 @@ void ConfigRevoHWWidget::flexiPortChanged(int index) if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_TELEMETRY)) { setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED); } - if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMTELEMETRY) - || isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_TELEMETRY)) { + if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMTELEMETRY)) { + setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM); + } + if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_TELEMETRY)) { setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED); } break; @@ -221,6 +236,13 @@ void ConfigRevoHWWidget::flexiPortChanged(int index) if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_GPS)) { setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED); } + if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMGPS)) { + setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM); + } + if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_GPS)) { + setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED); + } + break; case HwSettings::RM_FLEXIPORT_COMBRIDGE: m_ui->cbFlexiComSpeed->setVisible(true); @@ -230,6 +252,9 @@ void ConfigRevoHWWidget::flexiPortChanged(int index) if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE)) { setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED); } + if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMCOMBRIDGE)) { + setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM); + } break; case HwSettings::RM_FLEXIPORT_DEBUGCONSOLE: m_ui->cbFlexiComSpeed->setVisible(true); @@ -239,6 +264,42 @@ void ConfigRevoHWWidget::flexiPortChanged(int index) if (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DEBUGCONSOLE)) { setComboboxSelectedOption(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DISABLED); } + if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMDEBUGCONSOLE)) { + setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM); + } + if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DEBUGCONSOLE)) { + setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED); + } + break; + case HwSettings::RM_FLEXIPORT_OSDHK: + m_ui->lblFlexiSpeed->setVisible(false); + if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_OSDHK)) { + setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED); + } + break; + case HwSettings::RM_FLEXIPORT_MSP: + m_ui->lblFlexiSpeed->setVisible(false); + if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_MSP)) { + setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED); + } + if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_MSP)) { + setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED); + } + if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMMSP)) { + setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM); + } + break; + case HwSettings::RM_FLEXIPORT_MAVLINK: + m_ui->lblFlexiSpeed->setVisible(false); + if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_MAVLINK)) { + setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED); + } + if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_MAVLINK)) { + setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED); + } + if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMMAVLINK)) { + setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM); + } break; default: m_ui->lblFlexiSpeed->setVisible(false); @@ -265,8 +326,10 @@ void ConfigRevoHWWidget::mainPortChanged(int index) if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_TELEMETRY)) { setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED); } - if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMTELEMETRY) - || isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_TELEMETRY)) { + if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMTELEMETRY)) { + setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM); + } + if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_TELEMETRY)) { setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED); } break; @@ -279,6 +342,12 @@ void ConfigRevoHWWidget::mainPortChanged(int index) if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_GPS)) { setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED); } + if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMGPS)) { + setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM); + } + if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_GPS)) { + setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED); + } break; case HwSettings::RM_MAINPORT_COMBRIDGE: m_ui->cbMainComSpeed->setVisible(true); @@ -288,6 +357,9 @@ void ConfigRevoHWWidget::mainPortChanged(int index) if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_COMBRIDGE)) { setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED); } + if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMCOMBRIDGE)) { + setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM); + } break; case HwSettings::RM_MAINPORT_DEBUGCONSOLE: m_ui->cbMainComSpeed->setVisible(true); @@ -297,6 +369,42 @@ void ConfigRevoHWWidget::mainPortChanged(int index) if (isComboboxOptionSelected(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DEBUGCONSOLE)) { setComboboxSelectedOption(m_ui->cbUSBVCPFunction, HwSettings::USB_VCPPORT_DISABLED); } + if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMDEBUGCONSOLE)) { + setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM); + } + if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DEBUGCONSOLE)) { + setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED); + } + break; + case HwSettings::RM_MAINPORT_OSDHK: + m_ui->lblMainSpeed->setVisible(false); + if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_OSDHK)) { + setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED); + } + break; + case HwSettings::RM_MAINPORT_MSP: + m_ui->lblMainSpeed->setVisible(false); + if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_MSP)) { + setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED); + } + if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_MSP)) { + setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED); + } + if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMMSP)) { + setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM); + } + break; + case HwSettings::RM_MAINPORT_MAVLINK: + m_ui->lblMainSpeed->setVisible(false); + if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_MAVLINK)) { + setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED); + } + if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_MAVLINK)) { + setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_DISABLED); + } + if (isComboboxOptionSelected(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPMMAVLINK)) { + setComboboxSelectedOption(m_ui->cbRcvr, HwSettings::RM_RCVRPORT_PPM); + } break; default: m_ui->lblMainSpeed->setVisible(false); @@ -310,6 +418,12 @@ void ConfigRevoHWWidget::rcvrPortChanged(int index) m_ui->lblRcvrSpeed->setVisible(true); m_ui->cbRcvrTelemSpeed->setVisible(false); m_ui->cbRcvrComSpeed->setVisible(false); + m_ui->cbRcvrGPSSpeed->setVisible(false); + + // Add Gps protocol configuration + m_ui->cbRcvrGPSProtocol->setVisible(false); + m_ui->lblRcvrGPSProtocol->setVisible(false); + switch (getComboboxSelectedOption(m_ui->cbRcvr)) { case HwSettings::RM_RCVRPORT_TELEMETRY: @@ -324,6 +438,7 @@ void ConfigRevoHWWidget::rcvrPortChanged(int index) } break; case HwSettings::RM_RCVRPORT_COMBRIDGE: + case HwSettings::RM_RCVRPORT_PPMCOMBRIDGE: m_ui->cbRcvrComSpeed->setVisible(true); if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_COMBRIDGE)) { setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED); @@ -332,6 +447,51 @@ void ConfigRevoHWWidget::rcvrPortChanged(int index) setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED); } break; + case HwSettings::RM_RCVRPORT_DEBUGCONSOLE: + case HwSettings::RM_RCVRPORT_PPMDEBUGCONSOLE: + m_ui->cbRcvrComSpeed->setVisible(true); + if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DEBUGCONSOLE)) { + setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED); + } + if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_DEBUGCONSOLE)) { + setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED); + } + break; + case HwSettings::RM_RCVRPORT_GPS: + case HwSettings::RM_RCVRPORT_PPMGPS: + // Add Gps protocol configuration + m_ui->cbRcvrGPSProtocol->setVisible(true); + m_ui->lblRcvrGPSProtocol->setVisible(true); + + m_ui->cbRcvrGPSSpeed->setVisible(true); + + if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_GPS)) { + setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED); + } + if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_GPS)) { + setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED); + } + break; + case HwSettings::RM_RCVRPORT_MSP: + case HwSettings::RM_RCVRPORT_PPMMSP: + m_ui->lblRcvrSpeed->setVisible(false); + if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_MSP)) { + setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED); + } + if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_MSP)) { + setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED); + } + break; + case HwSettings::RM_RCVRPORT_MAVLINK: + case HwSettings::RM_RCVRPORT_PPMMAVLINK: + m_ui->lblRcvrSpeed->setVisible(false); + if (isComboboxOptionSelected(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_MAVLINK)) { + setComboboxSelectedOption(m_ui->cbFlexi, HwSettings::RM_FLEXIPORT_DISABLED); + } + if (isComboboxOptionSelected(m_ui->cbMain, HwSettings::RM_MAINPORT_MAVLINK)) { + setComboboxSelectedOption(m_ui->cbMain, HwSettings::RM_MAINPORT_DISABLED); + } + break; default: m_ui->lblRcvrSpeed->setVisible(false); break; diff --git a/ground/gcs/src/plugins/config/configrevohwwidget.ui b/ground/gcs/src/plugins/config/configrevohwwidget.ui index d09ef0373..f9daccfdc 100644 --- a/ground/gcs/src/plugins/config/configrevohwwidget.ui +++ b/ground/gcs/src/plugins/config/configrevohwwidget.ui @@ -655,6 +655,28 @@ + + + + + + + + 0 + 0 + + + + Protocol + + + Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft + + + + + + diff --git a/shared/uavobjectdefinition/hwsettings.xml b/shared/uavobjectdefinition/hwsettings.xml index bbbbd5200..ede6f7867 100644 --- a/shared/uavobjectdefinition/hwsettings.xml +++ b/shared/uavobjectdefinition/hwsettings.xml @@ -11,9 +11,9 @@ - + limits="%0905NE:PPM+PWM:PPM+Telemetry:PPM+ComBridge:PPM+MSP:PPM+MAVLink:PPM+GPS:Telemetry:ComBridge:MSP:MAVLink:GPS;"/> From e59359c8c2a69aca4207091528ba331d94687d6e Mon Sep 17 00:00:00 2001 From: Vladimir Zidar Date: Sat, 6 Aug 2016 03:25:28 +0200 Subject: [PATCH 07/20] LP-239 Exclude PPM+DebugConsole and DebugConsole from Nano RcvrPort. --- shared/uavobjectdefinition/hwsettings.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/shared/uavobjectdefinition/hwsettings.xml b/shared/uavobjectdefinition/hwsettings.xml index ede6f7867..4e4e6cb4d 100644 --- a/shared/uavobjectdefinition/hwsettings.xml +++ b/shared/uavobjectdefinition/hwsettings.xml @@ -13,7 +13,7 @@ + limits="%0905NE:PPM+PWM:PPM+Telemetry:PPM+DebugConsole:PPM+ComBridge:PPM+MSP:PPM+MAVLink:PPM+GPS:Telemetry:DebugConsole:ComBridge:MSP:MAVLink:GPS;"/> From 47b9bd3e4135fba7ccccbd4a00e2338e548e095d Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Tue, 9 Aug 2016 19:33:22 +0200 Subject: [PATCH 08/20] LP-379 Display ReceiverActivity in Rc Input tab --- .../src/plugins/config/configinputwidget.cpp | 30 ++ .../src/plugins/config/configinputwidget.h | 1 + ground/gcs/src/plugins/config/input.ui | 273 +++++++++++------- 3 files changed, 196 insertions(+), 108 deletions(-) diff --git a/ground/gcs/src/plugins/config/configinputwidget.cpp b/ground/gcs/src/plugins/config/configinputwidget.cpp index f350afcd3..061685593 100644 --- a/ground/gcs/src/plugins/config/configinputwidget.cpp +++ b/ground/gcs/src/plugins/config/configinputwidget.cpp @@ -203,6 +203,10 @@ ConfigInputWidget::ConfigInputWidget(QWidget *parent) : connect(wizardUi->wzCancel, SIGNAL(clicked()), this, SLOT(wzCancel())); connect(wizardUi->wzBack, SIGNAL(clicked()), this, SLOT(wzBack())); + connect(ReceiverActivity::GetInstance(getObjectManager()), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(updateReceiverActivityStatus())); + ui->receiverActivityStatus->setStyleSheet("QLabel { background-color: darkGreen; color: rgb(255, 255, 255); \ + border: 1px solid grey; border-radius: 5; margin:1px; font:bold;}"); + ui->stackedWidget->setCurrentIndex(0); QList widgets = QList() << ui->fmsModePos1 << ui->fmsModePos2 << ui->fmsModePos3 << ui->fmsModePos4 << ui->fmsModePos5 << ui->fmsModePos6; @@ -2117,6 +2121,32 @@ void ConfigInputWidget::forceOneFlightMode() manualSettingsObj->setData(manualSettingsData); } +void ConfigInputWidget::updateReceiverActivityStatus() +{ + ReceiverActivity *receiverActivity = ReceiverActivity::GetInstance(getObjectManager()); + + Q_ASSERT(receiverActivity); + + UAVObjectField *activeGroup = receiverActivity->getField(QString("ActiveGroup")); + Q_ASSERT(activeGroup); + + UAVObjectField *activeChannel = receiverActivity->getField(QString("ActiveChannel")); + Q_ASSERT(activeChannel); + + QString activeGroupText = activeGroup->getValue().toString(); + QString activeChannelText = activeChannel->getValue().toString(); + + if (activeGroupText != "None") { + ui->receiverActivityStatus->setText(tr("%1 input - Channel %2").arg(activeGroupText).arg(activeChannelText)); + ui->receiverActivityStatus->setStyleSheet("QLabel { background-color: green; color: rgb(255, 255, 255); \ + border: 1px solid grey; border-radius: 5; margin:1px; font:bold;}"); + } else { + ui->receiverActivityStatus->setText(tr("No activity")); + ui->receiverActivityStatus->setStyleSheet("QLabel { background-color: darkGreen; color: rgb(255, 255, 255); \ + border: 1px solid grey; border-radius: 5; margin:1px; font:bold;}"); + } +} + void ConfigInputWidget::failsafeFlightModeChanged(int index) { ui->failsafeFlightMode->setEnabled(index != -1); diff --git a/ground/gcs/src/plugins/config/configinputwidget.h b/ground/gcs/src/plugins/config/configinputwidget.h index a9bfaeca9..a110d62c3 100644 --- a/ground/gcs/src/plugins/config/configinputwidget.h +++ b/ground/gcs/src/plugins/config/configinputwidget.h @@ -230,6 +230,7 @@ private slots: void resetFlightModeSettings(); void resetActuatorSettings(); void forceOneFlightMode(); + void updateReceiverActivityStatus(); void failsafeFlightModeChanged(int index); void failsafeFlightModeCbToggled(bool checked); diff --git a/ground/gcs/src/plugins/config/input.ui b/ground/gcs/src/plugins/config/input.ui index f2421b745..dd45d70bf 100644 --- a/ground/gcs/src/plugins/config/input.ui +++ b/ground/gcs/src/plugins/config/input.ui @@ -136,7 +136,7 @@ 6 - + Input Channel Configuration @@ -281,114 +281,171 @@ - - - Calibration and Configuration Options + + + 0 - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 0 - 0 - - - - - 210 - 0 - - - - Start Transmitter Setup Wizard - - - false - - - false - - - false - - - false - - - false - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - true - - - - 0 - 0 - - - - - 210 - 0 - - - - false - - - Start Manual Calibration - - - true - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - + + + + Calibration and Configuration Options + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 0 + 0 + + + + + 240 + 0 + + + + Start Transmitter Setup Wizard + + + false + + + false + + + false + + + false + + + false + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + true + + + + 0 + 0 + + + + + 240 + 0 + + + + false + + + Start Manual Calibration + + + true + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + Receiver Activity + + + + + + true + + + + 300 + 30 + + + + Show receiver activity, input and channel +while moving one stick or switch at once. + + + border: 1px solid grey; +border-radius: 5; +margin:1px; +font:bold; + + + No activity + + + Qt::AlignCenter + + + + + + + From f0d6823d42040e1f1dc2e162075c5800d212019e Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Tue, 26 Jul 2016 01:14:49 +0200 Subject: [PATCH 09/20] LP-230 Update PFD for Autotune and new PathPlan alarm behavior. --- ground/gcs/src/share/qml/js/uav.js | 12 ++++++++---- ground/gcs/src/share/qml/pfd/Info.qml | 28 +++++++++++++-------------- 2 files changed, 22 insertions(+), 18 deletions(-) diff --git a/ground/gcs/src/share/qml/js/uav.js b/ground/gcs/src/share/qml/js/uav.js index 451cfb163..66d700a88 100644 --- a/ground/gcs/src/share/qml/js/uav.js +++ b/ground/gcs/src/share/qml/js/uav.js @@ -305,6 +305,10 @@ function estimatedTimeAlarmColor() { * Pathplan and Waypoints * */ +function isPathPlanEnabled() { + return (flightStatus.flightMode == FlightStatus.FlightMode.PathPlanner); +} + function isPathPlanValid() { return (systemAlarms.alarmPathPlan == SystemAlarms.Alarm.OK); } @@ -379,13 +383,13 @@ function isVtolPathFollowerSettingsThrustAuto() { function flightModeName() { return ["MANUAL", "STAB 1", "STAB 2", "STAB 3", "STAB 4", "STAB 5", "STAB 6", "POS HOLD", "COURSELOCK", "VEL ROAM", "HOME LEASH", "ABS POS", "RTB", - "LAND", "PATHPLAN", "POI", "AUTOCRUISE", "AUTOTAKEOFF"][flightStatus.flightMode]; + "LAND", "PATHPLAN", "POI", "AUTOCRUISE", "AUTOTAKEOFF", "AUTOTUNE"][flightStatus.flightMode]; } function flightModeColor() { return ["gray", "green", "green", "green", "green", "green", "green", "cyan", "cyan", "cyan", "cyan", "cyan", "cyan", - "cyan", "cyan", "cyan", "cyan", "cyan"][flightStatus.flightMode]; + "cyan", "cyan", "cyan", "cyan", "cyan", "cyan"][flightStatus.flightMode]; } function thrustMode() { @@ -399,12 +403,12 @@ function thrustModeName() { // Last "Auto" Thrust mode is added to UAVO enum list // Lower case modes are never displayed/used for Thrust return ["MANUAL", "rate", "ratetrainer", "attitude", "axislock", "weakleveling", "virtualbar", "acro+ ", "rattitude", - "ALT HOLD", "ALT VARIO", "CRUISECTRL", "AUTO"][thrustMode()] + "ALT HOLD", "ALT VARIO", "CRUISECTRL", "systemident", "AUTO"][thrustMode()] } function thrustModeColor() { return ["green", "grey", "grey", "grey", "grey", "grey", "grey", "grey", "grey", - "green", "green", "green", "cyan"][thrustMode()]; + "green", "green", "green", "grey", "cyan"][thrustMode()]; } function armStatusName() { diff --git a/ground/gcs/src/share/qml/pfd/Info.qml b/ground/gcs/src/share/qml/pfd/Info.qml index 827d2e039..0a0fb911e 100644 --- a/ground/gcs/src/share/qml/pfd/Info.qml +++ b/ground/gcs/src/share/qml/pfd/Info.qml @@ -134,7 +134,7 @@ Item { width: scaledBounds.width * sceneItem.width height: scaledBounds.height * sceneItem.height y: Math.floor(scaledBounds.y * sceneItem.height) - visible: UAV.isPathPlanValid() + visible: UAV.isPathPlanEnabled() } SvgElementPositionItem { @@ -143,7 +143,7 @@ Item { width: scaledBounds.width * sceneItem.width height: scaledBounds.height * sceneItem.height y: Math.floor(scaledBounds.y * sceneItem.height) - visible: UAV.isPathPlanValid() + visible: UAV.isPathPlanEnabled() Text { text: UAV.isPathPlanValid() ? " " + UAV.waypointHeading().toFixed(1) + "°" : " 0°" @@ -164,7 +164,7 @@ Item { width: scaledBounds.width * sceneItem.width height: scaledBounds.height * sceneItem.height y: Math.floor(scaledBounds.y * sceneItem.height) - visible: UAV.isPathPlanValid() + visible: UAV.isPathPlanEnabled() Text { text: UAV.isPathPlanValid() ? " " + UAV.waypointDistance().toFixed(0) + " m" : " 0 m" @@ -185,7 +185,7 @@ Item { width: scaledBounds.width * sceneItem.width height: scaledBounds.height * sceneItem.height y: Math.floor(scaledBounds.y * sceneItem.height) - visible: UAV.isPathPlanValid() + visible: UAV.isPathPlanEnabled() MouseArea { id: total_dist_mouseArea; anchors.fill: parent; cursorShape: Qt.PointingHandCursor; onClicked: reset_distance()} @@ -213,7 +213,7 @@ Item { width: scaledBounds.width * sceneItem.width height: scaledBounds.height * sceneItem.height y: Math.floor(scaledBounds.y * sceneItem.height) - visible: UAV.isPathPlanValid() + visible: UAV.isPathPlanEnabled() Text { text: UAV.isPathPlanValid() ? Utils.estimatedTimeOfArrival(UAV.waypointDistance(), UAV.currentVelocity()) : "00:00:00" @@ -234,7 +234,7 @@ Item { width: scaledBounds.width * sceneItem.width height: scaledBounds.height * sceneItem.height y: Math.floor(scaledBounds.y * sceneItem.height) - visible: UAV.isPathPlanValid() + visible: UAV.isPathPlanEnabled() Text { text: UAV.isPathPlanValid() ? UAV.currentWaypointActive() + " / " + UAV.waypointCount() : "0 / 0" @@ -255,7 +255,7 @@ Item { width: scaledBounds.width * sceneItem.width height: scaledBounds.height * sceneItem.height y: Math.floor(scaledBounds.y * sceneItem.height) - visible: UAV.isPathPlanValid() + visible: UAV.isPathPlanEnabled() Text { text: UAV.isPathPlanValid() ? UAV.pathModeDesired() : "" @@ -281,7 +281,7 @@ Item { width: scaledBounds.width * sceneItem.width height: scaledBounds.height * sceneItem.height y: scaledBounds.y * sceneItem.height - visible: (!UAV.isPathPlanValid() && UAV.batteryModuleEnabled()) + visible: (!UAV.isPathPlanEnabled() && UAV.batteryModuleEnabled()) Rectangle { anchors.fill: parent @@ -296,7 +296,7 @@ Item { width: scaledBounds.width * sceneItem.width height: scaledBounds.height * sceneItem.height y: Math.floor(scaledBounds.y * sceneItem.height) - visible: (!UAV.isPathPlanValid() && UAV.batteryModuleEnabled()) + visible: (!UAV.isPathPlanEnabled() && UAV.batteryModuleEnabled()) } SvgElementPositionItem { @@ -307,7 +307,7 @@ Item { width: scaledBounds.width * sceneItem.width height: scaledBounds.height * sceneItem.height y: scaledBounds.y * sceneItem.height - visible: (!UAV.isPathPlanValid() && UAV.batteryModuleEnabled()) + visible: (!UAV.isPathPlanEnabled() && UAV.batteryModuleEnabled()) Rectangle { anchors.fill: parent @@ -334,7 +334,7 @@ Item { width: scaledBounds.width * sceneItem.width height: scaledBounds.height * sceneItem.height y: scaledBounds.y * sceneItem.height - visible: (!UAV.isPathPlanValid() && UAV.batteryModuleEnabled()) + visible: (!UAV.isPathPlanEnabled() && UAV.batteryModuleEnabled()) Rectangle { anchors.fill: parent @@ -361,7 +361,7 @@ Item { width: scaledBounds.width * sceneItem.width height: scaledBounds.height * sceneItem.height y: scaledBounds.y * sceneItem.height - visible: (!UAV.isPathPlanValid() && UAV.batteryModuleEnabled()) + visible: (!UAV.isPathPlanEnabled() && UAV.batteryModuleEnabled()) Rectangle { anchors.fill: parent @@ -406,7 +406,7 @@ Item { width: scaledBounds.width * sceneItem.width height: scaledBounds.height * sceneItem.height y: Math.floor(scaledBounds.y * sceneItem.height) - visible: !UAV.isPathPlanValid() + visible: !UAV.isPathPlanEnabled() } SvgElementPositionItem { @@ -415,7 +415,7 @@ Item { width: scaledBounds.width * sceneItem.width height: scaledBounds.height * sceneItem.height y: Math.floor(scaledBounds.y * sceneItem.height) - visible: !UAV.isPathPlanValid() + visible: !UAV.isPathPlanEnabled() TooltipArea { text: "Reset distance counter" From 567c9b6f54a163fefd22640d032333382472c133 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Sun, 31 Jul 2016 14:10:25 +0200 Subject: [PATCH 10/20] LP-230 OplinkState update --- ground/gcs/src/share/qml/js/uav.js | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ground/gcs/src/share/qml/js/uav.js b/ground/gcs/src/share/qml/js/uav.js index 66d700a88..72e741943 100644 --- a/ground/gcs/src/share/qml/js/uav.js +++ b/ground/gcs/src/share/qml/js/uav.js @@ -260,7 +260,8 @@ function receiverQuality() { } function oplmLinkState() { - return ["Disabled", "Enabled", "Disconnected", "Connecting", "Connected"][opLinkStatus.linkState]; + return ["Disabled", "Enabled", "Binding", "Bound", "Disconnected", "Connecting", "Connected"][opLinkStatus.linkState]; + } /* From 14c247120322a85dbd9f372082ab7112ce95e258 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Sun, 31 Jul 2016 22:33:00 +0200 Subject: [PATCH 11/20] LP-230 Check if PFD enum in functions matches UAVO enum --- ground/gcs/src/share/qml/js/uav.js | 143 ++++++++++++++++++++++++----- 1 file changed, 120 insertions(+), 23 deletions(-) diff --git a/ground/gcs/src/share/qml/js/uav.js b/ground/gcs/src/share/qml/js/uav.js index 72e741943..796b3084d 100644 --- a/ground/gcs/src/share/qml/js/uav.js +++ b/ground/gcs/src/share/qml/js/uav.js @@ -32,6 +32,7 @@ .import UAVTalk.TakeOffLocation 1.0 as TakeOffLocation // Sensors +.import UAVTalk.AuxMagSettings 1.0 as AuxMagSettings .import UAVTalk.FlightBatterySettings 1.0 as FlightBatterySettings // State @@ -152,9 +153,16 @@ function isCC3D() { } function frameType() { - return ["FixedWing", "FixedWingElevon", "FixedWingVtail", "VTOL", "HeliCP", "QuadX", "QuadP", + var frameTypeText = ["FixedWing", "FixedWingElevon", "FixedWingVtail", "VTOL", "HeliCP", "QuadX", "QuadP", "Hexa+", "Octo+", "Custom", "HexaX", "HexaH", "OctoV", "OctoCoaxP", "OctoCoaxX", "OctoX", "HexaCoax", - "Tricopter", "GroundVehicleCar", "GroundVehicleDiff", "GroundVehicleMoto"][systemSettings.airframeType] + "Tricopter", "GroundVehicleCar", "GroundVehicleDiff", "GroundVehicleMoto"]; + + if (frameTypeText.length != SystemSettings.SystemSettingsConstants.AirframeTypeCount) { + console.log("uav.js: frameType() do not match systemSettings.airframeType uavo"); + return "Unknow" + } else { + return frameTypeText[systemSettings.airframeType] + } } function isVtolOrMultirotor() { @@ -223,12 +231,27 @@ function isOplmConnected() { } function magSourceName() { - return [magState.source == MagState.Source.Aux ? ["GPSv9", "Flexi", "I2C", "DJI"][auxMagSettings.type] + " " : ""] + - ["Invalid", "OnBoard", "ExtMag"][magState.source]; + var auxMagTypeText = ["GPSv9", "Flexi", "I2C", "DJI"]; + var magStateSourceText = ["Invalid", "OnBoard", "ExtMag"]; + + if ((auxMagTypeText.length != AuxMagSettings.AuxMagSettingsConstants.TypeCount) || + (magStateSourceText.length != MagState.MagStateConstants.SourceCount)) { + console.log("uav.js: magSourceName() do not match magState.source or auxMagSettings.type uavo"); + return "FixMe" + } else { + return [magState.source == MagState.Source.Aux ? auxMagTypeText[auxMagSettings.type] + " " : ""] + magStateSourceText[magState.source]; + } } function gpsSensorType() { - return ["Unknown", "NMEA", "UBX", "UBX7", "UBX8", "DJI"][gpsPositionSensor.sensorType] + var gpsSensorTypeText = ["Unknown", "NMEA", "UBX", "UBX7", "UBX8", "DJI"]; + + if (gpsSensorTypeText.length != GPSPositionSensor.GPSPositionSensorConstants.SensorTypeCount) { + console.log("uav.js: gpsSensorType() do not match gpsPositionSensor.sensorType uavo"); + return "FixMe" + } else { + return gpsSensorTypeText[gpsPositionSensor.sensorType]; + } } function gpsNumSat() { @@ -248,11 +271,25 @@ function gpsAltitude() { } function gpsStatus() { - return ["NO GPS", "NO FIX", "2D", "3D"][gpsPositionSensor.status]; + var gpsStatusText = ["NO GPS", "NO FIX", "2D", "3D"]; + + if (gpsStatusText.length != GPSPositionSensor.GPSPositionSensorConstants.StatusCount) { + console.log("uav.js: gpsStatus() do not match gpsPositionSensor.status uavo"); + return "FixMe" + } else { + return gpsStatusText[gpsPositionSensor.status]; + } } function fusionAlgorithm() { - return ["None", "Basic (No Nav)", "CompMag", "Comp+Mag+GPS", "EKFIndoor", "GPSNav (INS13)"][revoSettings.fusionAlgorithm]; + var fusionAlgorithmText = ["None", "Basic (No Nav)", "CompMag", "Comp+Mag+GPS", "EKFIndoor", "GPSNav (INS13)"]; + + if (fusionAlgorithmText.length != RevoSettings.RevoSettingsConstants.FusionAlgorithmCount) { + console.log("uav.js: fusionAlgorithm() do not match revoSettings.fusionAlgorithm uavo"); + return "FixMe" + } else { + return fusionAlgorithmText[revoSettings.fusionAlgorithm]; + } } function receiverQuality() { @@ -260,8 +297,14 @@ function receiverQuality() { } function oplmLinkState() { - return ["Disabled", "Enabled", "Binding", "Bound", "Disconnected", "Connecting", "Connected"][opLinkStatus.linkState]; + var oplmLinkStateText = ["Disabled", "Enabled", "Binding", "Bound", "Disconnected", "Connecting", "Connected"]; + if (oplmLinkStateText.length != OPLinkStatus.OPLinkStatusConstants.LinkStateCount) { + console.log("uav.js: oplmLinkState() do not match opLinkStatus.linkState uavo"); + return "FixMe" + } else { + return oplmLinkStateText[opLinkStatus.linkState]; + } } /* @@ -323,8 +366,15 @@ function isTakeOffLocationValid() { } function pathModeDesired() { - return ["GOTO ENDPOINT","FOLLOW VECTOR","CIRCLE RIGHT","CIRCLE LEFT","FIXED ATTITUDE", - "SET ACCESSORY","DISARM ALARM","LAND","BRAKE","VELOCITY","AUTO TAKEOFF"][pathDesired.mode] + var pathModeDesiredText = ["GOTO ENDPOINT","FOLLOW VECTOR","CIRCLE RIGHT","CIRCLE LEFT","FIXED ATTITUDE", + "SET ACCESSORY","DISARM ALARM","LAND","BRAKE","VELOCITY","AUTO TAKEOFF"]; + + if (pathModeDesiredText.length != PathDesired.PathDesiredConstants.ModeCount) { + console.log("uav.js: pathModeDesired() do not match pathDesired.mode uavo"); + return "FixMe" + } else { + return pathModeDesiredText[pathDesired.mode]; + } } function velocityDesiredDown() { @@ -382,15 +432,29 @@ function isVtolPathFollowerSettingsThrustAuto() { } function flightModeName() { - return ["MANUAL", "STAB 1", "STAB 2", "STAB 3", "STAB 4", "STAB 5", "STAB 6", - "POS HOLD", "COURSELOCK", "VEL ROAM", "HOME LEASH", "ABS POS", "RTB", - "LAND", "PATHPLAN", "POI", "AUTOCRUISE", "AUTOTAKEOFF", "AUTOTUNE"][flightStatus.flightMode]; + var flightModeNameText = ["MANUAL", "STAB 1", "STAB 2", "STAB 3", "STAB 4", "STAB 5", "STAB 6", + "POS HOLD", "COURSELOCK", "VEL ROAM", "HOME LEASH", "ABS POS", "RTB", + "LAND", "PATHPLAN", "POI", "AUTOCRUISE", "AUTOTAKEOFF", "AUTOTUNE"]; + + if (flightModeNameText.length != FlightStatus.FlightStatusConstants.FlightModeCount) { + console.log("uav.js: flightModeName() do not match flightStatus.flightMode uavo"); + return "UNKNOW" + } else { + return flightModeNameText[flightStatus.flightMode]; + } } function flightModeColor() { - return ["gray", "green", "green", "green", "green", "green", "green", - "cyan", "cyan", "cyan", "cyan", "cyan", "cyan", - "cyan", "cyan", "cyan", "cyan", "cyan", "cyan"][flightStatus.flightMode]; + var flightModeColorText = ["gray", "green", "green", "green", "green", "green", "green", + "cyan", "cyan", "cyan", "cyan", "cyan", "cyan", + "cyan", "cyan", "cyan", "cyan", "cyan", "cyan"]; + + if (flightModeColorText.length != FlightStatus.FlightStatusConstants.FlightModeCount) { + console.log("uav.js: flightModeColor() do not match flightStatus.flightMode uavo"); + return "gray" + } else { + return flightModeColorText[flightStatus.flightMode]; + } } function thrustMode() { @@ -401,23 +465,56 @@ function thrustMode() { } function thrustModeName() { - // Last "Auto" Thrust mode is added to UAVO enum list // Lower case modes are never displayed/used for Thrust - return ["MANUAL", "rate", "ratetrainer", "attitude", "axislock", "weakleveling", "virtualbar", "acro+ ", "rattitude", - "ALT HOLD", "ALT VARIO", "CRUISECTRL", "systemident", "AUTO"][thrustMode()] + var thrustModeNameText = ["MANUAL", "rate", "ratetrainer", "attitude", "axislock", "weakleveling", "virtualbar", "acro+ ", "rattitude", + "ALT HOLD", "ALT VARIO", "CRUISECTRL", "systemident"]; + + // Last "Auto" Thrust mode is added to current UAVO enum list for display. + thrustModeNameText.push("AUTO"); + + if (thrustModeNameText.length != StabilizationDesired.StabilizationDesiredConstants.StabilizationModeCount + 1) { + console.log("uav.js: thrustModeName() do not match stabilizationDesired.StabilizationMode uavo"); + return "FixMe" + } else { + return thrustModeNameText[thrustMode()]; + } } function thrustModeColor() { - return ["green", "grey", "grey", "grey", "grey", "grey", "grey", "grey", "grey", - "green", "green", "green", "grey", "cyan"][thrustMode()]; + var thrustModeColorText = ["green", "grey", "grey", "grey", "grey", "grey", "grey", "grey", "grey", + "green", "green", "green", "grey"]; + + // Add the cyan color for AUTO + thrustModeColorText.push("cyan"); + + if (thrustModeColorText.length != StabilizationDesired.StabilizationDesiredConstants.StabilizationModeCount + 1) { + console.log("uav.js: thrustModeColor() do not match stabilizationDesired.StabilizationMode uavo"); + return "gray" + } else { + return thrustModeColorText[thrustMode()]; + } } function armStatusName() { - return ["DISARMED","ARMING","ARMED"][flightStatus.armed]; + var armStatusNameText = ["DISARMED","ARMING","ARMED"]; + + if (armStatusNameText.length != FlightStatus.FlightStatusConstants.ArmedCount) { + console.log("uav.js: armStatusName() do not match flightStatus.armed uavo"); + return "FixMe" + } else { + return armStatusNameText[flightStatus.armed]; + } } function armStatusColor() { - return ["gray", "orange", "green"][flightStatus.armed]; + var armStatusColorText = ["gray", "orange", "green"]; + + if (armStatusColorText.length != FlightStatus.FlightStatusConstants.ArmedCount) { + console.log("uav.js: armStatusColor() do not match flightStatus.armed uavo"); + return "gray" + } else { + return armStatusColorText[flightStatus.armed]; + } } /* From c71345117b0f82deaee8bd539c6717456f6faf58 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Thu, 4 Aug 2016 10:08:10 +0200 Subject: [PATCH 12/20] LP-230 Set "FixMe" in all wrong enums to be consistent --- ground/gcs/src/share/qml/js/uav.js | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ground/gcs/src/share/qml/js/uav.js b/ground/gcs/src/share/qml/js/uav.js index 796b3084d..a8e767a96 100644 --- a/ground/gcs/src/share/qml/js/uav.js +++ b/ground/gcs/src/share/qml/js/uav.js @@ -159,7 +159,7 @@ function frameType() { if (frameTypeText.length != SystemSettings.SystemSettingsConstants.AirframeTypeCount) { console.log("uav.js: frameType() do not match systemSettings.airframeType uavo"); - return "Unknow" + return "FixMe" } else { return frameTypeText[systemSettings.airframeType] } @@ -438,7 +438,7 @@ function flightModeName() { if (flightModeNameText.length != FlightStatus.FlightStatusConstants.FlightModeCount) { console.log("uav.js: flightModeName() do not match flightStatus.flightMode uavo"); - return "UNKNOW" + return "FixMe" } else { return flightModeNameText[flightStatus.flightMode]; } From 1d0c472dbdaa993fdc1c5299b02124469f52aaa9 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Sat, 13 Aug 2016 13:50:56 +0200 Subject: [PATCH 13/20] LP-230 Remove unneeded code --- ground/gcs/src/share/qml/js/uav.js | 39 ++++++++++-------------------- 1 file changed, 13 insertions(+), 26 deletions(-) diff --git a/ground/gcs/src/share/qml/js/uav.js b/ground/gcs/src/share/qml/js/uav.js index a8e767a96..b92ed926f 100644 --- a/ground/gcs/src/share/qml/js/uav.js +++ b/ground/gcs/src/share/qml/js/uav.js @@ -160,9 +160,8 @@ function frameType() { if (frameTypeText.length != SystemSettings.SystemSettingsConstants.AirframeTypeCount) { console.log("uav.js: frameType() do not match systemSettings.airframeType uavo"); return "FixMe" - } else { - return frameTypeText[systemSettings.airframeType] } + return frameTypeText[systemSettings.airframeType] } function isVtolOrMultirotor() { @@ -238,9 +237,8 @@ function magSourceName() { (magStateSourceText.length != MagState.MagStateConstants.SourceCount)) { console.log("uav.js: magSourceName() do not match magState.source or auxMagSettings.type uavo"); return "FixMe" - } else { - return [magState.source == MagState.Source.Aux ? auxMagTypeText[auxMagSettings.type] + " " : ""] + magStateSourceText[magState.source]; } + return [magState.source == MagState.Source.Aux ? auxMagTypeText[auxMagSettings.type] + " " : ""] + magStateSourceText[magState.source]; } function gpsSensorType() { @@ -249,9 +247,8 @@ function gpsSensorType() { if (gpsSensorTypeText.length != GPSPositionSensor.GPSPositionSensorConstants.SensorTypeCount) { console.log("uav.js: gpsSensorType() do not match gpsPositionSensor.sensorType uavo"); return "FixMe" - } else { - return gpsSensorTypeText[gpsPositionSensor.sensorType]; } + return gpsSensorTypeText[gpsPositionSensor.sensorType]; } function gpsNumSat() { @@ -276,9 +273,8 @@ function gpsStatus() { if (gpsStatusText.length != GPSPositionSensor.GPSPositionSensorConstants.StatusCount) { console.log("uav.js: gpsStatus() do not match gpsPositionSensor.status uavo"); return "FixMe" - } else { - return gpsStatusText[gpsPositionSensor.status]; } + return gpsStatusText[gpsPositionSensor.status]; } function fusionAlgorithm() { @@ -287,9 +283,8 @@ function fusionAlgorithm() { if (fusionAlgorithmText.length != RevoSettings.RevoSettingsConstants.FusionAlgorithmCount) { console.log("uav.js: fusionAlgorithm() do not match revoSettings.fusionAlgorithm uavo"); return "FixMe" - } else { - return fusionAlgorithmText[revoSettings.fusionAlgorithm]; } + return fusionAlgorithmText[revoSettings.fusionAlgorithm]; } function receiverQuality() { @@ -302,9 +297,8 @@ function oplmLinkState() { if (oplmLinkStateText.length != OPLinkStatus.OPLinkStatusConstants.LinkStateCount) { console.log("uav.js: oplmLinkState() do not match opLinkStatus.linkState uavo"); return "FixMe" - } else { - return oplmLinkStateText[opLinkStatus.linkState]; } + return oplmLinkStateText[opLinkStatus.linkState]; } /* @@ -372,9 +366,8 @@ function pathModeDesired() { if (pathModeDesiredText.length != PathDesired.PathDesiredConstants.ModeCount) { console.log("uav.js: pathModeDesired() do not match pathDesired.mode uavo"); return "FixMe" - } else { - return pathModeDesiredText[pathDesired.mode]; } + return pathModeDesiredText[pathDesired.mode]; } function velocityDesiredDown() { @@ -439,9 +432,8 @@ function flightModeName() { if (flightModeNameText.length != FlightStatus.FlightStatusConstants.FlightModeCount) { console.log("uav.js: flightModeName() do not match flightStatus.flightMode uavo"); return "FixMe" - } else { - return flightModeNameText[flightStatus.flightMode]; } + return flightModeNameText[flightStatus.flightMode]; } function flightModeColor() { @@ -452,9 +444,8 @@ function flightModeColor() { if (flightModeColorText.length != FlightStatus.FlightStatusConstants.FlightModeCount) { console.log("uav.js: flightModeColor() do not match flightStatus.flightMode uavo"); return "gray" - } else { - return flightModeColorText[flightStatus.flightMode]; } + return flightModeColorText[flightStatus.flightMode]; } function thrustMode() { @@ -475,9 +466,8 @@ function thrustModeName() { if (thrustModeNameText.length != StabilizationDesired.StabilizationDesiredConstants.StabilizationModeCount + 1) { console.log("uav.js: thrustModeName() do not match stabilizationDesired.StabilizationMode uavo"); return "FixMe" - } else { - return thrustModeNameText[thrustMode()]; } + return thrustModeNameText[thrustMode()]; } function thrustModeColor() { @@ -490,9 +480,8 @@ function thrustModeColor() { if (thrustModeColorText.length != StabilizationDesired.StabilizationDesiredConstants.StabilizationModeCount + 1) { console.log("uav.js: thrustModeColor() do not match stabilizationDesired.StabilizationMode uavo"); return "gray" - } else { - return thrustModeColorText[thrustMode()]; } + return thrustModeColorText[thrustMode()]; } function armStatusName() { @@ -501,9 +490,8 @@ function armStatusName() { if (armStatusNameText.length != FlightStatus.FlightStatusConstants.ArmedCount) { console.log("uav.js: armStatusName() do not match flightStatus.armed uavo"); return "FixMe" - } else { - return armStatusNameText[flightStatus.armed]; } + return armStatusNameText[flightStatus.armed]; } function armStatusColor() { @@ -512,9 +500,8 @@ function armStatusColor() { if (armStatusColorText.length != FlightStatus.FlightStatusConstants.ArmedCount) { console.log("uav.js: armStatusColor() do not match flightStatus.armed uavo"); return "gray" - } else { - return armStatusColorText[flightStatus.armed]; } + return armStatusColorText[flightStatus.armed]; } /* From cba2184caf9db5df66ffb23e60e1a3be0850e4d3 Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Wed, 17 Aug 2016 19:57:29 +0200 Subject: [PATCH 14/20] LP-381 - Adds circular buffer and run writes within a separate callback --- flight/pios/common/pios_debuglog.c | 128 +++++++++++++------- shared/uavobjectdefinition/callbackinfo.xml | 3 + 2 files changed, 86 insertions(+), 45 deletions(-) diff --git a/flight/pios/common/pios_debuglog.c b/flight/pios/common/pios_debuglog.c index 8f400ec59..e688674bb 100644 --- a/flight/pios/common/pios_debuglog.c +++ b/flight/pios/common/pios_debuglog.c @@ -32,6 +32,7 @@ #include "pios.h" #include "uavobjectmanager.h" #include "debuglogentry.h" +#include "callbackinfo.h" // global definitions #ifdef PIOS_INCLUDE_DEBUGLOG @@ -39,14 +40,9 @@ // Global variables extern uintptr_t pios_user_fs_id; // flash filesystem for logging -#if defined(PIOS_INCLUDE_FREERTOS) static xSemaphoreHandle mutex = 0; #define mutexlock() xSemaphoreTakeRecursive(mutex, portMAX_DELAY) #define mutexunlock() xSemaphoreGiveRecursive(mutex) -#else -#define mutexlock() -#define mutexunlock() -#endif static bool logging_enabled = false; #define MAX_CONSECUTIVE_FAILS_COUNT 10 @@ -54,10 +50,12 @@ static bool log_is_full = false; static uint8_t fails_count = 0; static uint16_t flightnum = 0; static uint16_t lognum = 0; -static DebugLogEntryData *buffer = 0; -#if !defined(PIOS_INCLUDE_FREERTOS) -static DebugLogEntryData staticbuffer; -#endif + +#define BUFFERS_COUNT 2 +static DebugLogEntryData *current_buffer = 0; +static DebugLogEntryData *buffers[BUFFERS_COUNT] = { 0, 0 }; +static uint8_t current_write_buffer_index; +static uint8_t next_read_buffer_index; #define LOG_ENTRY_MAX_DATA_SIZE (sizeof(((DebugLogEntryData *)0)->Data)) #define LOG_ENTRY_HEADER_SIZE (sizeof(DebugLogEntryData) - LOG_ENTRY_MAX_DATA_SIZE) @@ -66,23 +64,33 @@ static DebugLogEntryData staticbuffer; static uint32_t used_buffer_space = 0; +#define CBTASK_PRIORITY CALLBACK_TASK_AUXILIARY +#define CALLBACK_PRIORITY CALLBACK_PRIORITY_LOW +#define CB_TIMEOUT 100 +#define STACK_SIZE_BYTES 512 +static DelayedCallbackInfo *callbackHandle; + /* Private Function Prototypes */ static void enqueue_data(uint32_t objid, uint16_t instid, size_t size, uint8_t *data); static bool write_current_buffer(); +static void writeTask(); +static uint8_t get_blocks_free(); /** * @brief Initialize the log facility */ void PIOS_DEBUGLOG_Initialize() { -#if defined(PIOS_INCLUDE_FREERTOS) if (!mutex) { - mutex = xSemaphoreCreateRecursiveMutex(); - buffer = pios_malloc(sizeof(DebugLogEntryData)); + mutex = xSemaphoreCreateRecursiveMutex(); + for (uint32_t i = 0; i < BUFFERS_COUNT; i++) { + buffers[i] = pios_malloc(sizeof(DebugLogEntryData)); + } + current_write_buffer_index = 0; + next_read_buffer_index = 0; + current_buffer = buffers[current_write_buffer_index]; } -#else - buffer = &staticbuffer; -#endif - if (!buffer) { + + if (!current_buffer) { return; } mutexlock(); @@ -91,10 +99,12 @@ void PIOS_DEBUGLOG_Initialize() fails_count = 0; used_buffer_space = 0; log_is_full = false; - while (PIOS_FLASHFS_ObjLoad(pios_user_fs_id, LOG_GET_FLIGHT_OBJID(flightnum), lognum, (uint8_t *)buffer, sizeof(DebugLogEntryData)) == 0) { + while (PIOS_FLASHFS_ObjLoad(pios_user_fs_id, LOG_GET_FLIGHT_OBJID(flightnum), lognum, (uint8_t *)current_buffer, sizeof(DebugLogEntryData)) == 0) { flightnum++; } mutexunlock(); + callbackHandle = PIOS_CALLBACKSCHEDULER_Create(&writeTask, CALLBACK_PRIORITY, CBTASK_PRIORITY, CALLBACKINFO_RUNNING_DEBUGLOG, STACK_SIZE_BYTES); + PIOS_CALLBACKSCHEDULER_Schedule(callbackHandle, CB_TIMEOUT, CALLBACK_UPDATEMODE_LATER); } @@ -122,7 +132,7 @@ void PIOS_DEBUGLOG_Enable(uint8_t enabled) */ void PIOS_DEBUGLOG_UAVObject(uint32_t objid, uint16_t instid, size_t size, uint8_t *data) { - if (!logging_enabled || !buffer || log_is_full) { + if (!logging_enabled || !current_buffer || log_is_full) { return; } mutexlock(); @@ -139,7 +149,7 @@ void PIOS_DEBUGLOG_UAVObject(uint32_t objid, uint16_t instid, size_t size, uint8 */ void PIOS_DEBUGLOG_Printf(char *format, ...) { - if (!logging_enabled || !buffer || log_is_full) { + if (!logging_enabled || !current_buffer || log_is_full) { return; } @@ -150,19 +160,19 @@ void PIOS_DEBUGLOG_Printf(char *format, ...) if (used_buffer_space) { write_current_buffer(); } - memset(buffer->Data, 0xff, sizeof(buffer->Data)); - vsnprintf((char *)buffer->Data, sizeof(buffer->Data), (char *)format, args); - buffer->Flight = flightnum; + memset(current_buffer->Data, 0xff, sizeof(current_buffer->Data)); + vsnprintf((char *)current_buffer->Data, sizeof(current_buffer->Data), (char *)format, args); + current_buffer->Flight = flightnum; - buffer->FlightTime = PIOS_DELAY_GetuS(); + current_buffer->FlightTime = PIOS_DELAY_GetuS(); - buffer->Entry = lognum; - buffer->Type = DEBUGLOGENTRY_TYPE_TEXT; - buffer->ObjectID = 0; - buffer->InstanceID = 0; - buffer->Size = strlen((const char *)buffer->Data); + current_buffer->Entry = lognum; + current_buffer->Type = DEBUGLOGENTRY_TYPE_TEXT; + current_buffer->ObjectID = 0; + current_buffer->InstanceID = 0; + current_buffer->Size = strlen((const char *)current_buffer->Data); - if (PIOS_FLASHFS_ObjSave(pios_user_fs_id, LOG_GET_FLIGHT_OBJID(flightnum), lognum, (uint8_t *)buffer, sizeof(DebugLogEntryData)) == 0) { + if (PIOS_FLASHFS_ObjSave(pios_user_fs_id, LOG_GET_FLIGHT_OBJID(flightnum), lognum, (uint8_t *)current_buffer, sizeof(DebugLogEntryData)) == 0) { lognum++; } mutexunlock(); @@ -233,21 +243,21 @@ void enqueue_data(uint32_t objid, uint16_t instid, size_t size, uint8_t *data) // start a new block if (!used_buffer_space) { - entry = buffer; - memset(buffer->Data, 0xff, sizeof(buffer->Data)); + entry = current_buffer; + memset(current_buffer->Data, 0xff, sizeof(current_buffer->Data)); used_buffer_space += size; } else { // if an instance is being filled and there is enough space, does enqueues new data. if (used_buffer_space + size + LOG_ENTRY_HEADER_SIZE > LOG_ENTRY_MAX_DATA_SIZE) { - buffer->Type = DEBUGLOGENTRY_TYPE_MULTIPLEUAVOBJECTS; + current_buffer->Type = DEBUGLOGENTRY_TYPE_MULTIPLEUAVOBJECTS; if (!write_current_buffer()) { return; } - entry = buffer; - memset(buffer->Data, 0xff, sizeof(buffer->Data)); + entry = current_buffer; + memset(current_buffer->Data, 0xff, sizeof(current_buffer->Data)); used_buffer_space += size; } else { - entry = (DebugLogEntryData *)&buffer->Data[used_buffer_space]; + entry = (DebugLogEntryData *)¤t_buffer->Data[used_buffer_space]; used_buffer_space += size + LOG_ENTRY_HEADER_SIZE; } } @@ -258,8 +268,8 @@ void enqueue_data(uint32_t objid, uint16_t instid, size_t size, uint8_t *data) entry->Type = DEBUGLOGENTRY_TYPE_UAVOBJECT; entry->ObjectID = objid; entry->InstanceID = instid; - if (size > sizeof(buffer->Data)) { - size = sizeof(buffer->Data); + if (size > sizeof(current_buffer->Data)) { + size = sizeof(current_buffer->Data); } entry->Size = size; @@ -268,18 +278,46 @@ void enqueue_data(uint32_t objid, uint16_t instid, size_t size, uint8_t *data) bool write_current_buffer() { - // not enough space, write the block and start a new one - if (PIOS_FLASHFS_ObjSave(pios_user_fs_id, LOG_GET_FLIGHT_OBJID(flightnum), lognum, (uint8_t *)buffer, sizeof(DebugLogEntryData)) == 0) { - lognum++; - fails_count = 0; + PIOS_CALLBACKSCHEDULER_Dispatch(callbackHandle); + // Check if queue is full + + if (get_blocks_free() > 0) { + current_write_buffer_index = (current_write_buffer_index + 1) % BUFFERS_COUNT; + current_buffer = buffers[current_write_buffer_index]; used_buffer_space = 0; + return true; } else { - if (fails_count++ > MAX_CONSECUTIVE_FAILS_COUNT) { - log_is_full = true; - } return false; } - return true; +} + +static uint8_t get_blocks_free() +{ + uint8_t used_blocks = current_write_buffer_index - next_read_buffer_index; + + if (current_write_buffer_index < next_read_buffer_index) { + used_blocks = (BUFFERS_COUNT - next_read_buffer_index) + current_write_buffer_index; + } + return (BUFFERS_COUNT - used_blocks) - 1; +} + +static void writeTask() +{ + if (current_write_buffer_index != next_read_buffer_index) { + // not enough space, write the block and start a new one + if (PIOS_FLASHFS_ObjSave(pios_user_fs_id, + LOG_GET_FLIGHT_OBJID(flightnum), lognum, + (uint8_t *)buffers[next_read_buffer_index], + sizeof(DebugLogEntryData)) == 0) { + next_read_buffer_index = (next_read_buffer_index + 1) % BUFFERS_COUNT; + lognum++; + fails_count = 0; + } else { + if (fails_count++ > MAX_CONSECUTIVE_FAILS_COUNT) { + log_is_full = true; + } + } + } } #endif /* ifdef PIOS_INCLUDE_DEBUGLOG */ /** diff --git a/shared/uavobjectdefinition/callbackinfo.xml b/shared/uavobjectdefinition/callbackinfo.xml index 598e4988a..17d32018e 100644 --- a/shared/uavobjectdefinition/callbackinfo.xml +++ b/shared/uavobjectdefinition/callbackinfo.xml @@ -12,6 +12,7 @@ PathPlanner0 PathPlanner1 ManualControl + DebugLog @@ -25,6 +26,7 @@ PathPlanner0 PathPlanner1 ManualControl + DebugLog @@ -42,6 +44,7 @@ PathPlanner0 PathPlanner1 ManualControl + DebugLog From 5a17e26ceae19ba189ba029f3eb9e998b42e6927 Mon Sep 17 00:00:00 2001 From: James Duley Date: Sun, 14 Aug 2016 12:22:45 +0100 Subject: [PATCH 15/20] LP-380: default to using system qt and osg on Linux --- Makefile | 7 +++++-- make/tools.mk | 3 ++- 2 files changed, 7 insertions(+), 3 deletions(-) diff --git a/Makefile b/Makefile index b0d25c206..b916c719a 100644 --- a/Makefile +++ b/Makefile @@ -140,9 +140,12 @@ export UAVOBJGENERATOR GCS_BUILD_CONF := release # Set extra configuration -GCS_EXTRA_CONF += osg copy_osg +GCS_EXTRA_CONF += osg +ifeq ($(UNAME), Darwin) + GCS_EXTRA_CONF += copy_osg +endif ifeq ($(UNAME), Windows) - GCS_EXTRA_CONF += osgearth + GCS_EXTRA_CONF += osgearth copy_osg endif ############################## diff --git a/make/tools.mk b/make/tools.mk index 15ab8ff4f..2f22d0539 100644 --- a/make/tools.mk +++ b/make/tools.mk @@ -165,7 +165,8 @@ endif BUILD_SDK_TARGETS := arm_sdk ifeq ($(UNAME), Windows) BUILD_SDK_TARGETS += nsis mesawin -else +endif +ifeq ($(UNAME), Darwin) BUILD_SDK_TARGETS += qt_sdk osg endif ALL_SDK_TARGETS := $(BUILD_SDK_TARGETS) gtest uncrustify doxygen From 71367dcaab04f356fb1bab5b1596745a41a5701f Mon Sep 17 00:00:00 2001 From: James Duley Date: Sun, 14 Aug 2016 12:25:56 +0100 Subject: [PATCH 16/20] LP-380: turn off waring about osg not found like other warnings --- make/tools.mk | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/make/tools.mk b/make/tools.mk index 2f22d0539..ecf0462e0 100644 --- a/make/tools.mk +++ b/make/tools.mk @@ -830,7 +830,7 @@ ifeq ($(shell [ -d "$(OSG_SDK_DIR)" ] && $(ECHO) "exists"), exists) export OSG_SDK_DIR := $(OSG_SDK_DIR) else # not installed, hope it's in the path... - $(info $(EMPTY) WARNING $(call toprel, $(OSG_SDK_DIR)) not found (make osg_install), using system PATH) + # $(info $(EMPTY) WARNING $(call toprel, $(OSG_SDK_DIR)) not found (make osg_install), using system PATH) endif .PHONY: osg_version @@ -853,7 +853,7 @@ ifeq ($(shell [ -d "$(OSGEARTH_SDK_DIR)" ] && $(ECHO) "exists"), exists) export OSGEARTH_SDK_DIR := $(OSGEARTH_SDK_DIR) else # not installed, hope it's in the path... - $(info $(EMPTY) WARNING $(call toprel, $(OSGEARTH_SDK_DIR)) not found (make osgearth_install), using system PATH) + # $(info $(EMPTY) WARNING $(call toprel, $(OSGEARTH_SDK_DIR)) not found (make osgearth_install), using system PATH) endif .PHONY: osgearth_version From 87c05c2d6335410bd61990e67b1f2d1fff1755b7 Mon Sep 17 00:00:00 2001 From: James Duley Date: Tue, 16 Aug 2016 21:12:11 +0100 Subject: [PATCH 17/20] Drop fedora 22 support --- package/linux/rpmspec.in | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/package/linux/rpmspec.in b/package/linux/rpmspec.in index 330a36f7b..5d92b4ed6 100644 --- a/package/linux/rpmspec.in +++ b/package/linux/rpmspec.in @@ -25,7 +25,7 @@ BuildRequires: qt5-qtsvg-devel BuildRequires: qt5-qttools-devel BuildRequires: qt5-qttranslations BuildRequires: OpenSceneGraph-devel -%{!?fc22:BuildRequires: osgearth-devel} +BuildRequires: osgearth-devel BuildRequires: dwz BuildRequires: pkgconfig BuildRequires: python @@ -41,7 +41,7 @@ Requires: qt5-qtscript Requires: qt5-qtserialport Requires: qt5-qtsvg Requires: OpenSceneGraph-libs -%{!?fc22:Requires: osgearth} +Requires: osgearth %description From 798248ef24259158853f64cdae5aa545775d9c0d Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Sun, 21 Aug 2016 04:57:15 +0200 Subject: [PATCH 18/20] LP-387 Analog port: Add DAC pin as input - Fix pin mapping. --- flight/targets/boards/sparky2/pios_board.h | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/flight/targets/boards/sparky2/pios_board.h b/flight/targets/boards/sparky2/pios_board.h index 26bbb7e53..63986b0fb 100644 --- a/flight/targets/boards/sparky2/pios_board.h +++ b/flight/targets/boards/sparky2/pios_board.h @@ -310,13 +310,14 @@ extern uint32_t pios_packet_handler; // ADC // PIOS_ADC_PinGet(0) = Current sensor // PIOS_ADC_PinGet(1) = Voltage sensor -// PIOS_ADC_PinGet(4) = VREF -// PIOS_ADC_PinGet(5) = Temperature sensor +// PIOS_ADC_PinGet(7) = VREF +// PIOS_ADC_PinGet(8) = Temperature sensor // ------------------------- #define PIOS_DMA_PIN_CONFIG \ { \ - { GPIOC, GPIO_Pin_3, ADC_Channel_13, false }, /* batt/sonar pin 3 */ \ - { GPIOC, GPIO_Pin_2, ADC_Channel_12, false }, /* batt/sonar pin 4 */ \ + { GPIOC, GPIO_Pin_2, ADC_Channel_12, false }, /* Analog port pin 3 */ \ + { GPIOC, GPIO_Pin_3, ADC_Channel_13, false }, /* Analog port pin 4 */ \ + { GPIOA, GPIO_Pin_4, ADC_Channel_4, false }, /* Analog port pin2 (DAC) */ \ { GPIOA, GPIO_Pin_3, ADC_Channel_3, false }, /* Servo pin 3 */ \ { GPIOA, GPIO_Pin_2, ADC_Channel_2, false }, /* Servo pin 4 */ \ { GPIOA, GPIO_Pin_1, ADC_Channel_1, false }, /* Servo pin 5 */ \ @@ -328,12 +329,12 @@ extern uint32_t pios_packet_handler; /* we have to do all this to satisfy the PIOS_ADC_MAX_SAMPLES define in pios_adc.h */ /* which is annoying because this then determines the rate at which we generate buffer turnover events */ /* the objective here is to get enough buffer space to support 100Hz averaging rate */ -#define PIOS_ADC_NUM_CHANNELS 8 +#define PIOS_ADC_NUM_CHANNELS 9 #define PIOS_ADC_MAX_OVERSAMPLING 2 #define PIOS_ADC_USE_ADC2 0 #define PIOS_ADC_USE_TEMP_SENSOR -#define PIOS_ADC_TEMPERATURE_PIN 7 +#define PIOS_ADC_TEMPERATURE_PIN 8 // ------------------------- // USB From d8cef1eb9c00bc4db64981ac323a371e1080ae66 Mon Sep 17 00:00:00 2001 From: James Duley Date: Sun, 14 Aug 2016 12:00:31 +0100 Subject: [PATCH 19/20] LP-380: add make config_help and rework OSG config --- .travis.yml | 4 +- Makefile | 77 +++++++++++++++++++++++++++++++++----- bitbucket-pipelines.yml | 4 +- package/linux/debian/rules | 2 +- package/linux/rpmspec.in | 2 +- 5 files changed, 74 insertions(+), 15 deletions(-) diff --git a/.travis.yml b/.travis.yml index 97fee1190..ff5c026fd 100644 --- a/.travis.yml +++ b/.travis.yml @@ -8,10 +8,10 @@ before_install: - sudo add-apt-repository ppa:librepilot/tools -y - sudo apt-get update -q - sudo apt-get install -y libc6-i386 libudev-dev libusb-1.0-0-dev libsdl1.2-dev python libopenscenegraph-dev libosgearth-dev qt56-meta-minimal qt56svg qt56script qt56serialport qt56multimedia qt56translations qt56tools - - make arm_sdk_install + - make build_sdk_install script: - - make config_new CCACHE=ccache GCS_EXTRA_CONF='osg osgearth' + - make config_new CCACHE=ccache GCS_WITH_OSGEARTH=1 - make all_flight - make opfw_resource - make gcs diff --git a/Makefile b/Makefile index b916c719a..e0806b3e3 100644 --- a/Makefile +++ b/Makefile @@ -127,11 +127,20 @@ include $(ROOT_DIR)/make/tools.mk # We almost need to consider autoconf/automake instead of this ifeq ($(UNAME), Linux) - UAVOBJGENERATOR := $(BUILD_DIR)/uavobjgenerator/uavobjgenerator + UAVOBJGENERATOR := $(BUILD_DIR)/uavobjgenerator/uavobjgenerator + GCS_WITH_OSG := 1 + GCS_WITH_OSGEARTH := 0 + GCS_COPY_OSG := 0 else ifeq ($(UNAME), Darwin) - UAVOBJGENERATOR := $(BUILD_DIR)/uavobjgenerator/uavobjgenerator + UAVOBJGENERATOR := $(BUILD_DIR)/uavobjgenerator/uavobjgenerator + GCS_WITH_OSG := 1 + GCS_WITH_OSGEARTH := 0 + GCS_COPY_OSG := 1 else ifeq ($(UNAME), Windows) UAVOBJGENERATOR := $(BUILD_DIR)/uavobjgenerator/uavobjgenerator.exe + GCS_WITH_OSG := 1 + GCS_WITH_OSGEARTH := 1 + GCS_COPY_OSG := 1 endif export UAVOBJGENERATOR @@ -140,12 +149,14 @@ export UAVOBJGENERATOR GCS_BUILD_CONF := release # Set extra configuration -GCS_EXTRA_CONF += osg -ifeq ($(UNAME), Darwin) - GCS_EXTRA_CONF += copy_osg -endif -ifeq ($(UNAME), Windows) - GCS_EXTRA_CONF += osgearth copy_osg +ifeq ($(GCS_WITH_OSG), 1) + GCS_EXTRA_CONF += osg + ifeq ($(GCS_COPY_OSG), 1) + GCS_EXTRA_CONF += copy_osg + endif + ifeq ($(GCS_WITH_OSGEARTH), 1) + GCS_EXTRA_CONF += osgearth + endif endif ############################## @@ -513,12 +524,59 @@ config_append: .PHONY: config_show config_show: - @cat $(CONFIG_FILE) + @cat $(CONFIG_FILE) | sed 's/override *//' .PHONY: config_clean config_clean: rm -f $(CONFIG_FILE) +.PHONY: config_help +config_help: + @$(ECHO) " The build system has a simple system for persistent configuration" + @$(ECHO) + @$(ECHO) " To set persistent configuration variables you, for example, do:" + @$(ECHO) " $(MAKE) config_new CCACHE=ccache GCS_WITH_OSG=0" + @$(ECHO) + @$(ECHO) " To add to the existing configuration do:" + @$(ECHO) " $(MAKE) config_append GCS_BUILD_CONF=debug" + @$(ECHO) + @$(ECHO) " To reset the configuration to defaults do:" + @$(ECHO) " $(MAKE) config_clean" + @$(ECHO) + @$(ECHO) " To show the current configuration:" + @$(ECHO) " $(MAKE) config_show" + @$(ECHO) + @$(ECHO) " You can override any make variable this way, but these are the useful ones" + @$(ECHO) " shown with their current (or default values):" + @$(ECHO) + @$(ECHO) " GCS_BUILD_CONF=$(GCS_BUILD_CONF)" + @$(ECHO) " GCS build type" + @$(ECHO) " Options: debug or release" + @$(ECHO) + @$(ECHO) " GCS_WITH_OSG=$(GCS_WITH_OSG)" + @$(ECHO) " Build the GCS with OpenSceneGraph support, this enables the PFD Model View" + @$(ECHO) " Options: 0 or 1" + @$(ECHO) + @$(ECHO) " GCS_WITH_OSGEARTH=$(GCS_WITH_OSGEARTH)" + @$(ECHO) " Build the GCS with osgEarth support, this enables extra PFD terrain views" + @$(ECHO) " Options: 0 or 1" + @$(ECHO) + @$(ECHO) " GCS_COPY_OSG=$(GCS_COPY_OSG)" + @$(ECHO) " Copy OpenSceneGraph/osgEarth libraries into the build" + @$(ECHO) " (Needed unless using system versions)" + @$(ECHO) " Options: 0 or 1" + @$(ECHO) + @$(ECHO) " CCACHE=$(CCACHE)" + @$(ECHO) " A prefix to compiler invocations, usually 'ccache' or 'path/to/ccache'" + @$(ECHO) + @$(ECHO) " QMAKE=$(QMAKE)" + @$(ECHO) " How to invoke qmake, usually 'qmake', 'qmake-qt5' or 'path/to/qmake'" + @$(ECHO) + @$(ECHO) " WITH_PREBUILT_FIRMWARE=$(WITH_PREBUILT_FIRMWARE)" + @$(ECHO) " Set to path of prebuilt firmware or empty to build firmware when needed" +# TODO: add other things like downloads and tools directories, linux make install parameters + + ############################## # @@ -672,6 +730,7 @@ help: @$(ECHO) " docs_all_clean - Delete all generated documentation" @$(ECHO) @$(ECHO) " [Configuration]" + @$(ECHO) " config_help - Show information on how to configure the build" @$(ECHO) " config_new - Place your make arguments in the config file" @$(ECHO) " config_append - Place your make arguments in the config file but append" @$(ECHO) " config_clean - Removes the config file" diff --git a/bitbucket-pipelines.yml b/bitbucket-pipelines.yml index 813e8b97f..f61779c9a 100644 --- a/bitbucket-pipelines.yml +++ b/bitbucket-pipelines.yml @@ -5,8 +5,8 @@ pipelines: - add-apt-repository ppa:librepilot/tools -y - apt-get update -q - apt-get install -y libc6-i386 libudev-dev libusb-1.0-0-dev libsdl1.2-dev python libopenscenegraph-dev libosgearth-dev qt56-meta-minimal qt56svg qt56script qt56serialport qt56multimedia qt56translations qt56tools - - make arm_sdk_install - - make config_new GCS_EXTRA_CONF='osg osgearth' + - make build_sdk_install + - make config_new GCS_WITH_OSGEARTH=1 - make all_flight - make opfw_resource - make gcs diff --git a/package/linux/debian/rules b/package/linux/debian/rules index 2fb9d4eb1..59ffe7c2a 100755 --- a/package/linux/debian/rules +++ b/package/linux/debian/rules @@ -12,7 +12,7 @@ export DH_OPTIONS dh $@ override_dh_auto_configure: - $(MAKE) config_new GCS_EXTRA_CONF='osg osgearth' WITH_PREBUILT_FW=$(CURDIR)/firmware + $(MAKE) config_new GCS_WITH_OSGEARTH=1 WITH_PREBUILT_FW=$(CURDIR)/firmware override_dh_auto_build: dh_auto_build -- opfw_resource gcs diff --git a/package/linux/rpmspec.in b/package/linux/rpmspec.in index 5d92b4ed6..87b0f5b07 100644 --- a/package/linux/rpmspec.in +++ b/package/linux/rpmspec.in @@ -60,7 +60,7 @@ make config_new \ QMAKE=qmake-qt5 \ udevrulesdir=%{_udevrulesdir} \ WITH_PREBUILT_FW=$(pwd)/build/firmware \ - GCS_EXTRA_CONF='osg%{!?fc22: osgearth}' + GCS_WITH_OSGEARTH=1 make %{?_smp_mflags} opfw_resource gcs From a27548d062e083914804e981118e97bae17df673 Mon Sep 17 00:00:00 2001 From: James Duley Date: Tue, 16 Aug 2016 22:54:30 +0100 Subject: [PATCH 20/20] LP-380: Turn osgEarth on by default on Linux --- .travis.yml | 2 +- Makefile | 2 +- bitbucket-pipelines.yml | 1 - package/linux/debian/rules | 2 +- package/linux/rpmspec.in | 3 +-- 5 files changed, 4 insertions(+), 6 deletions(-) diff --git a/.travis.yml b/.travis.yml index ff5c026fd..06c8fe0e8 100644 --- a/.travis.yml +++ b/.travis.yml @@ -11,7 +11,7 @@ before_install: - make build_sdk_install script: - - make config_new CCACHE=ccache GCS_WITH_OSGEARTH=1 + - make config_new CCACHE=ccache - make all_flight - make opfw_resource - make gcs diff --git a/Makefile b/Makefile index e0806b3e3..ff952865c 100644 --- a/Makefile +++ b/Makefile @@ -129,7 +129,7 @@ include $(ROOT_DIR)/make/tools.mk ifeq ($(UNAME), Linux) UAVOBJGENERATOR := $(BUILD_DIR)/uavobjgenerator/uavobjgenerator GCS_WITH_OSG := 1 - GCS_WITH_OSGEARTH := 0 + GCS_WITH_OSGEARTH := 1 GCS_COPY_OSG := 0 else ifeq ($(UNAME), Darwin) UAVOBJGENERATOR := $(BUILD_DIR)/uavobjgenerator/uavobjgenerator diff --git a/bitbucket-pipelines.yml b/bitbucket-pipelines.yml index f61779c9a..b73f5e6aa 100644 --- a/bitbucket-pipelines.yml +++ b/bitbucket-pipelines.yml @@ -6,7 +6,6 @@ pipelines: - apt-get update -q - apt-get install -y libc6-i386 libudev-dev libusb-1.0-0-dev libsdl1.2-dev python libopenscenegraph-dev libosgearth-dev qt56-meta-minimal qt56svg qt56script qt56serialport qt56multimedia qt56translations qt56tools - make build_sdk_install - - make config_new GCS_WITH_OSGEARTH=1 - make all_flight - make opfw_resource - make gcs diff --git a/package/linux/debian/rules b/package/linux/debian/rules index 59ffe7c2a..e636c8a1d 100755 --- a/package/linux/debian/rules +++ b/package/linux/debian/rules @@ -12,7 +12,7 @@ export DH_OPTIONS dh $@ override_dh_auto_configure: - $(MAKE) config_new GCS_WITH_OSGEARTH=1 WITH_PREBUILT_FW=$(CURDIR)/firmware + $(MAKE) config_new WITH_PREBUILT_FW=$(CURDIR)/firmware override_dh_auto_build: dh_auto_build -- opfw_resource gcs diff --git a/package/linux/rpmspec.in b/package/linux/rpmspec.in index 87b0f5b07..35cbc4aca 100644 --- a/package/linux/rpmspec.in +++ b/package/linux/rpmspec.in @@ -59,8 +59,7 @@ make config_new \ prefix=%{_prefix} \ QMAKE=qmake-qt5 \ udevrulesdir=%{_udevrulesdir} \ - WITH_PREBUILT_FW=$(pwd)/build/firmware \ - GCS_WITH_OSGEARTH=1 + WITH_PREBUILT_FW=$(pwd)/build/firmware make %{?_smp_mflags} opfw_resource gcs