diff --git a/HISTORY.txt b/HISTORY.txt index aba9effab..b9e59ac1d 100644 --- a/HISTORY.txt +++ b/HISTORY.txt @@ -1,5 +1,13 @@ Short summary of changes. For a complete list see the git log. +2012-01-02 +CC FW now supports USB Virtual Com Port (VCP/CDC) in addition to the original HID interface +New ComUsbBridge module can bridge any serial port to the USB CDC port +CC FW now detects repeated faults during init and boots with default hwsettings + +2012-01-02 +Added new camera stabilization features: AxisLock mode and LPF. + 2011-12-10 Merged a change that sorts the UAVO fields based on size. Because this changes all of the objects, erase all existing flash files based on this. diff --git a/Makefile b/Makefile index aaffbb1fc..1159fdac5 100644 --- a/Makefile +++ b/Makefile @@ -235,7 +235,7 @@ STM32FLASH_DIR := $(TOOLS_DIR)/stm32flash .PHONY: stm32flash_install stm32flash_install: STM32FLASH_URL := http://stm32flash.googlecode.com/svn/trunk -stm32flash_install: STM32FLASH_REV := 52 +stm32flash_install: STM32FLASH_REV := 61 stm32flash_install: stm32flash_clean # download the source $(V0) @echo " DOWNLOAD $(STM32FLASH_URL) @ r$(STM32FLASH_REV)" diff --git a/artwork/Font/OpenPilot.ttf b/artwork/Font/OpenPilot.ttf index c3bb5765c..c61597d72 100644 Binary files a/artwork/Font/OpenPilot.ttf and b/artwork/Font/OpenPilot.ttf differ diff --git a/flight/Bootloaders/AHRS/inc/pios_config.h b/flight/Bootloaders/AHRS/inc/pios_config.h index b24e0fc5b..82344e2ad 100644 --- a/flight/Bootloaders/AHRS/inc/pios_config.h +++ b/flight/Bootloaders/AHRS/inc/pios_config.h @@ -36,5 +36,6 @@ #define PIOS_INCLUDE_BL_HELPER #define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT #define PIOS_INCLUDE_GPIO +#define PIOS_INCLUDE_IAP #endif /* PIOS_CONFIG_H */ diff --git a/flight/Bootloaders/CopterControl/Makefile b/flight/Bootloaders/CopterControl/Makefile index ddcdca1c8..8c5d870ac 100644 --- a/flight/Bootloaders/CopterControl/Makefile +++ b/flight/Bootloaders/CopterControl/Makefile @@ -105,18 +105,20 @@ SRC += $(PIOSSTM32F10X)/pios_debug.c SRC += $(PIOSSTM32F10X)/pios_gpio.c SRC += $(PIOSSTM32F10X)/pios_iap.c - # PIOS USB related files (seperated to make code maintenance more easy) +SRC += $(PIOSSTM32F10X)/pios_usb.c +SRC += $(PIOSSTM32F10X)/pios_usbhook.c SRC += $(PIOSSTM32F10X)/pios_usb_hid.c -SRC += $(PIOSSTM32F10X)/pios_usb_hid_desc.c SRC += $(PIOSSTM32F10X)/pios_usb_hid_istr.c -SRC += $(PIOSSTM32F10X)/pios_usb_hid_prop.c SRC += $(PIOSSTM32F10X)/pios_usb_hid_pwr.c -SRC += $(PIOSSTM32F10X)/pios_bl_helper.c +SRC += $(OPSYSTEM)/pios_usb_board_data.c +SRC += $(PIOSCOMMON)/pios_usb_desc_hid_only.c ## PIOS Hardware (Common) SRC += $(PIOSCOMMON)/pios_board_info.c -SRC += $(PIOSCOMMON)/pios_com.c +SRC += $(PIOSCOMMON)/pios_com_msg.c +SRC += $(PIOSCOMMON)/pios_bl_helper.c +SRC += $(PIOSCOMMON)/pios_iap.c SRC += $(PIOSCOMMON)/printf-stdarg.c ## Libraries for flight calculations diff --git a/flight/Bootloaders/CopterControl/inc/pios_config.h b/flight/Bootloaders/CopterControl/inc/pios_config.h index faa0cff54..3eb2c281a 100644 --- a/flight/Bootloaders/CopterControl/inc/pios_config.h +++ b/flight/Bootloaders/CopterControl/inc/pios_config.h @@ -32,15 +32,16 @@ #define PIOS_CONFIG_H #define PIOS_INCLUDE_BL_HELPER #define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT -#define USB_HID /* Enable/Disable PiOS Modules */ #define PIOS_INCLUDE_DELAY #define PIOS_INCLUDE_IRQ #define PIOS_INCLUDE_LED #define PIOS_INCLUDE_SYS +#define PIOS_INCLUDE_USB #define PIOS_INCLUDE_USB_HID -#define PIOS_INCLUDE_COM +#define PIOS_INCLUDE_COM_MSG #define PIOS_INCLUDE_GPIO +#define PIOS_INCLUDE_IAP #define PIOS_NO_GPS #endif /* PIOS_CONFIG_H */ diff --git a/flight/Bootloaders/CopterControl/inc/pios_usb.h b/flight/Bootloaders/CopterControl/inc/pios_usb.h deleted file mode 100644 index f95a31835..000000000 --- a/flight/Bootloaders/CopterControl/inc/pios_usb.h +++ /dev/null @@ -1,85 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_USB USB Functions - * @brief PIOS USB interface code - * @{ - * - * @file pios_usb.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) - * @brief USB 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_USB_H -#define PIOS_USB_H - -/* Local defines */ -/* Following settings allow to customise the USB device descriptor */ -#ifndef PIOS_USB_VENDOR_ID -#define PIOS_USB_VENDOR_ID 0x20A0 -#endif - -#ifndef PIOS_USB_VENDOR_STR -#define PIOS_USB_VENDOR_STR "openpilot.org" -#endif - -#ifndef PIOS_USB_PRODUCT_STR -#define PIOS_USB_PRODUCT_STR "CopterControl" -#endif - -#ifndef PIOS_USB_PRODUCT_ID -#define PIOS_USB_PRODUCT_ID 0x415B -#endif - -#ifndef PIOS_USB_VERSION_ID -#define PIOS_USB_VERSION_ID 0x0401 /* CopterControl (04) Bootloader (01) */ -#endif - -/* Internal defines which are used by PIOS USB HID (don't touch) */ -#define PIOS_USB_EP_NUM 2 - -/* Buffer table base address */ -#define PIOS_USB_BTABLE_ADDRESS 0x000 - -/* EP0 rx/tx buffer base address */ -#define PIOS_USB_ENDP0_RXADDR 0x040 -#define PIOS_USB_ENDP0_TXADDR 0x080 - -/* EP1 Rx/Tx buffer base address for HID driver */ -#define PIOS_USB_ENDP1_TXADDR 0x0C0 -#define PIOS_USB_ENDP1_RXADDR 0x100 - -/* Global Variables */ -extern void (*pEpInt_IN[7])(void); -extern void (*pEpInt_OUT[7])(void); - -/* Public Functions */ -extern int32_t PIOS_USB_Init(uint32_t mode); -extern int32_t PIOS_USB_IsInitialized(void); -extern int32_t PIOS_USB_CableConnected(void); - -#endif /* PIOS_USB_H */ - -/** - * @} - * @} - */ diff --git a/flight/Bootloaders/CopterControl/inc/pios_usb_board_data.h b/flight/Bootloaders/CopterControl/inc/pios_usb_board_data.h new file mode 100644 index 000000000..f1accee17 --- /dev/null +++ b/flight/Bootloaders/CopterControl/inc/pios_usb_board_data.h @@ -0,0 +1,51 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB_BOARD Board specific USB definitions + * @brief Board specific USB definitions + * @{ + * + * @file pios_usb_board_data.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Board specific USB definitions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_USB_BOARD_DATA_H +#define PIOS_USB_BOARD_DATA_H + +#define PIOS_USB_BOARD_HID_DATA_LENGTH 64 + +#define PIOS_USB_BOARD_EP_NUM 2 + +#include "pios_usb_defs.h" /* struct usb_* */ + +#define PIOS_USB_BOARD_PRODUCT_ID USB_PRODUCT_ID_COPTERCONTROL +#define PIOS_USB_BOARD_DEVICE_VER USB_OP_DEVICE_VER(USB_OP_BOARD_ID_COPTERCONTROL, USB_OP_BOARD_MODE_BL) + +/* + * The bootloader uses a simplified report structure + * BL: ... + * FW: ... + * This define changes the behaviour in pios_usb_hid.c + */ +#define PIOS_USB_BOARD_BL_HID_HAS_NO_LENGTH_BYTE + +#endif /* PIOS_USB_BOARD_DATA_H */ diff --git a/flight/Bootloaders/CopterControl/main.c b/flight/Bootloaders/CopterControl/main.c index aa375a49c..7a61ae9e9 100644 --- a/flight/Bootloaders/CopterControl/main.c +++ b/flight/Bootloaders/CopterControl/main.c @@ -32,6 +32,7 @@ #include "usb_lib.h" #include "pios_iap.h" #include "fifo_buffer.h" +#include "pios_com_msg.h" /* Prototype of PIOS_Board_Init() function */ extern void PIOS_Board_Init(void); extern void FLASH_Download(); @@ -62,7 +63,7 @@ uint8_t JumpToApp = FALSE; uint8_t GO_dfu = FALSE; uint8_t USB_connected = FALSE; uint8_t User_DFU_request = FALSE; -static uint8_t mReceive_Buffer[64]; +static uint8_t mReceive_Buffer[63]; /* Private function prototypes -----------------------------------------------*/ uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count); uint8_t processRX(); @@ -198,10 +199,8 @@ uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count) { } uint8_t processRX() { - while (PIOS_COM_ReceiveBufferUsed(PIOS_COM_TELEM_USB) >= 63) { - if (PIOS_COM_ReceiveBuffer(PIOS_COM_TELEM_USB, mReceive_Buffer, 63, 0) == 63) { - processComand(mReceive_Buffer); - } + if (PIOS_COM_MSG_Receive(PIOS_COM_TELEM_USB, mReceive_Buffer, sizeof(mReceive_Buffer))) { + processComand(mReceive_Buffer); } return TRUE; } diff --git a/flight/Bootloaders/CopterControl/op_dfu.c b/flight/Bootloaders/CopterControl/op_dfu.c index b45e1e798..9f98d3394 100644 --- a/flight/Bootloaders/CopterControl/op_dfu.c +++ b/flight/Bootloaders/CopterControl/op_dfu.c @@ -30,6 +30,7 @@ #include "pios.h" #include "op_dfu.h" #include "pios_bl_helper.h" +#include "pios_com_msg.h" #include //programmable devices Device devicesTable[10]; @@ -294,6 +295,10 @@ void processComand(uint8_t *xReceive_Buffer) { sendData(Buffer + 1, 63); break; case JumpFW: + if (Data == 0x5AFE) { + /* Force board into safe mode */ + PIOS_IAP_WriteBootCount(0xFFFF); + } FLASH_Lock(); JumpToApp = 1; break; @@ -442,9 +447,7 @@ uint32_t CalcFirmCRC() { } void sendData(uint8_t * buf, uint16_t size) { - PIOS_COM_SendBuffer(PIOS_COM_TELEM_USB, buf, size); - if (DeviceState == downloading) - PIOS_DELAY_WaitmS(20);//this is an hack, we should check wtf is wrong with hid + PIOS_COM_MSG_Send(PIOS_COM_TELEM_USB, buf, size); } bool flash_read(uint8_t * buffer, uint32_t adr, DFUProgType type) { diff --git a/flight/Bootloaders/CopterControl/pios_board.c b/flight/Bootloaders/CopterControl/pios_board.c index 28a280f4b..a70537fcc 100644 --- a/flight/Bootloaders/CopterControl/pios_board.c +++ b/flight/Bootloaders/CopterControl/pios_board.c @@ -27,24 +27,18 @@ // *********************************************************************************** -#if defined(PIOS_INCLUDE_COM) +#if defined(PIOS_INCLUDE_COM_MSG) -#include +#include -#define PIOS_COM_TELEM_USB_RX_BUF_LEN 192 -#define PIOS_COM_TELEM_USB_TX_BUF_LEN 192 - -static uint8_t pios_com_telem_usb_rx_buffer[PIOS_COM_TELEM_USB_RX_BUF_LEN]; -static uint8_t pios_com_telem_usb_tx_buffer[PIOS_COM_TELEM_USB_TX_BUF_LEN]; - -#endif /* PIOS_INCLUDE_COM */ +#endif /* PIOS_INCLUDE_COM_MSG */ // *********************************************************************************** -#if defined(PIOS_INCLUDE_USB_HID) -#include "pios_usb_hid_priv.h" +#if defined(PIOS_INCLUDE_USB) +#include "pios_usb_priv.h" -static const struct pios_usb_hid_cfg pios_usb_hid_main_cfg = { +static const struct pios_usb_cfg pios_usb_main_cfg = { .irq = { .init = { .NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn, @@ -54,9 +48,22 @@ static const struct pios_usb_hid_cfg pios_usb_hid_main_cfg = { }, }, }; -#endif /* PIOS_INCLUDE_USB_HID */ -extern const struct pios_com_driver pios_usb_com_driver; +#include "pios_usb_board_data_priv.h" +#include "pios_usb_desc_hid_only_priv.h" + +#endif /* PIOS_INCLUDE_USB */ + +#if defined(PIOS_INCLUDE_USB_HID) +#include + +const struct pios_usb_hid_cfg pios_usb_hid_cfg = { + .data_if = 0, + .data_rx_ep = 1, + .data_tx_ep = 1, +}; + +#endif /* PIOS_INCLUDE_USB_HID */ uint32_t pios_com_telem_usb_id; @@ -83,19 +90,28 @@ void PIOS_Board_Init(void) { /* Initialize the PiOS library */ PIOS_GPIO_Init(); -#if defined(PIOS_INCLUDE_USB_HID) +#if defined(PIOS_INCLUDE_USB) + /* Initialize board specific USB data */ + PIOS_USB_BOARD_DATA_Init(); + + /* Activate the HID-only USB configuration */ + PIOS_USB_DESC_HID_ONLY_Init(); + + uint32_t pios_usb_id; + if (PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg)) { + PIOS_Assert(0); + } +#if defined(PIOS_INCLUDE_USB_HID) && defined(PIOS_INCLUDE_COM_MSG) uint32_t pios_usb_hid_id; - if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_main_cfg)) { + if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) { PIOS_Assert(0); } -#if defined(PIOS_INCLUDE_COM) - if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_com_driver, pios_usb_hid_id, - pios_com_telem_usb_rx_buffer, sizeof(pios_com_telem_usb_rx_buffer), - pios_com_telem_usb_tx_buffer, sizeof(pios_com_telem_usb_tx_buffer))) { + if (PIOS_COM_MSG_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id)) { PIOS_Assert(0); } -#endif /* PIOS_INCLUDE_COM */ -#endif /* PIOS_INCLUDE_USB_HID */ +#endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_COM_MSG */ + +#endif /* PIOS_INCLUDE_USB */ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_CRC, ENABLE);//TODO Tirar diff --git a/flight/Bootloaders/CopterControl/pios_usb_board_data.c b/flight/Bootloaders/CopterControl/pios_usb_board_data.c new file mode 100644 index 000000000..4f02ce424 --- /dev/null +++ b/flight/Bootloaders/CopterControl/pios_usb_board_data.c @@ -0,0 +1,123 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB_BOARD Board specific USB definitions + * @brief Board specific USB definitions + * @{ + * + * @file pios_usb_board_data.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Board specific USB definitions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "pios_usb_board_data.h" /* struct usb_*, USB_* */ +#include "pios_sys.h" /* PIOS_SYS_SerialNumberGet */ +#include "pios_usbhook.h" /* PIOS_USBHOOK_* */ + +static const uint8_t usb_product_id[28] = { + sizeof(usb_product_id), + USB_DESC_TYPE_STRING, + 'C', 0, + 'o', 0, + 'p', 0, + 't', 0, + 'e', 0, + 'r', 0, + 'C', 0, + 'o', 0, + 'n', 0, + 't', 0, + 'r', 0, + 'o', 0, + 'l', 0, +}; + +static uint8_t usb_serial_number[52] = { + sizeof(usb_serial_number), + USB_DESC_TYPE_STRING, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0 +}; + +static const struct usb_string_langid usb_lang_id = { + .bLength = sizeof(usb_lang_id), + .bDescriptorType = USB_DESC_TYPE_STRING, + .bLangID = htousbs(USB_LANGID_ENGLISH_UK), +}; + +static const uint8_t usb_vendor_id[28] = { + sizeof(usb_vendor_id), + USB_DESC_TYPE_STRING, + 'o', 0, + 'p', 0, + 'e', 0, + 'n', 0, + 'p', 0, + 'i', 0, + 'l', 0, + 'o', 0, + 't', 0, + '.', 0, + 'o', 0, + 'r', 0, + 'g', 0 +}; + +int32_t PIOS_USB_BOARD_DATA_Init(void) +{ + /* Load device serial number into serial number string */ + uint8_t sn[25]; + PIOS_SYS_SerialNumberGet((char *)sn); + for (uint8_t i = 0; sn[i] != '\0' && (2 * i) < usb_serial_number[0]; i++) { + usb_serial_number[2 + 2 * i] = sn[i]; + } + + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_PRODUCT, (uint8_t *)&usb_product_id, sizeof(usb_product_id)); + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_SERIAL, (uint8_t *)&usb_serial_number, sizeof(usb_serial_number)); + + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_LANG, (uint8_t *)&usb_lang_id, sizeof(usb_lang_id)); + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_VENDOR, (uint8_t *)&usb_vendor_id, sizeof(usb_vendor_id)); + + return 0; +} diff --git a/flight/Bootloaders/OpenPilot/Makefile b/flight/Bootloaders/OpenPilot/Makefile index ebc45b0e7..e2b577237 100644 --- a/flight/Bootloaders/OpenPilot/Makefile +++ b/flight/Bootloaders/OpenPilot/Makefile @@ -111,14 +111,17 @@ SRC += $(PIOSSTM32F10X)/pios_iap.c SRC += $(PIOSSTM32F10X)/pios_bl_helper.c # PIOS USB related files (seperated to make code maintenance more easy) +SRC += $(PIOSSTM32F10X)/pios_usb.c +SRC += $(PIOSSTM32F10X)/pios_usbhook.c SRC += $(PIOSSTM32F10X)/pios_usb_hid.c -SRC += $(PIOSSTM32F10X)/pios_usb_hid_desc.c SRC += $(PIOSSTM32F10X)/pios_usb_hid_istr.c -SRC += $(PIOSSTM32F10X)/pios_usb_hid_prop.c SRC += $(PIOSSTM32F10X)/pios_usb_hid_pwr.c +SRC += $(OPSYSTEM)/pios_usb_board_data.c +SRC += $(PIOSCOMMON)/pios_usb_desc_hid_only.c ## PIOS Hardware (Common) SRC += $(PIOSCOMMON)/pios_board_info.c +SRC += $(PIOSCOMMON)/pios_com_msg.c SRC += $(PIOSCOMMON)/pios_com.c SRC += $(PIOSCOMMON)/pios_opahrs_v0.c SRC += $(PIOSCOMMON)/pios_opahrs_proto.c @@ -290,7 +293,7 @@ CSTANDARD = -std=gnu99 # Flags for C and C++ (arm-elf-gcc/arm-elf-g++) ifeq ($(DEBUG),YES) -CFLAGS = -DDEBUG +CFLAGS += -DDEBUG endif CFLAGS += -g$(DEBUGF) diff --git a/flight/Bootloaders/OpenPilot/inc/pios_config.h b/flight/Bootloaders/OpenPilot/inc/pios_config.h index c4ace5f90..932c1a913 100644 --- a/flight/Bootloaders/OpenPilot/inc/pios_config.h +++ b/flight/Bootloaders/OpenPilot/inc/pios_config.h @@ -31,7 +31,6 @@ #define PIOS_CONFIG_H #define PIOS_INCLUDE_BL_HELPER #define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT -#define USB_HID /* Enable/Disable PiOS Modules */ #define PIOS_INCLUDE_DELAY #define PIOS_INCLUDE_IRQ @@ -39,10 +38,13 @@ #define PIOS_INCLUDE_SPI #define PIOS_INCLUDE_SYS #define PIOS_INCLUDE_USART +#define PIOS_INCLUDE_USB #define PIOS_INCLUDE_USB_HID #define PIOS_INCLUDE_OPAHRS #define PIOS_INCLUDE_COM +#define PIOS_INCLUDE_COM_MSG #define PIOS_INCLUDE_GPIO +#define PIOS_INCLUDE_IAP //#define DEBUG_SSP /* Defaults for Logging */ diff --git a/flight/Bootloaders/OpenPilot/inc/pios_usb.h b/flight/Bootloaders/OpenPilot/inc/pios_usb.h deleted file mode 100644 index bca8a883b..000000000 --- a/flight/Bootloaders/OpenPilot/inc/pios_usb.h +++ /dev/null @@ -1,85 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_USB USB Functions - * @brief PIOS USB interface code - * @{ - * - * @file pios_usb.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) - * @brief USB 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_USB_H -#define PIOS_USB_H - -/* Local defines */ -/* Following settings allow to customise the USB device descriptor */ -#ifndef PIOS_USB_VENDOR_ID -#define PIOS_USB_VENDOR_ID 0x20A0 -#endif - -#ifndef PIOS_USB_VENDOR_STR -#define PIOS_USB_VENDOR_STR "openpilot.org" -#endif - -#ifndef PIOS_USB_PRODUCT_STR -#define PIOS_USB_PRODUCT_STR "OpenPilot" -#endif - -#ifndef PIOS_USB_PRODUCT_ID -#define PIOS_USB_PRODUCT_ID 0x415A -#endif - -#ifndef PIOS_USB_VERSION_ID -#define PIOS_USB_VERSION_ID 0x0101 /* OpenPilot (01) Bootloader (01) */ -#endif - -/* Internal defines which are used by PIOS USB HID (don't touch) */ -#define PIOS_USB_EP_NUM 2 - -/* Buffer table base address */ -#define PIOS_USB_BTABLE_ADDRESS 0x000 - -/* EP0 rx/tx buffer base address */ -#define PIOS_USB_ENDP0_RXADDR 0x040 -#define PIOS_USB_ENDP0_TXADDR 0x080 - -/* EP1 Rx/Tx buffer base address for HID driver */ -#define PIOS_USB_ENDP1_TXADDR 0x0C0 -#define PIOS_USB_ENDP1_RXADDR 0x100 - -/* Global Variables */ -extern void (*pEpInt_IN[7])(void); -extern void (*pEpInt_OUT[7])(void); - -/* Public Functions */ -extern int32_t PIOS_USB_Init(uint32_t mode); -extern int32_t PIOS_USB_IsInitialized(void); -extern int32_t PIOS_USB_CableConnected(void); - -#endif /* PIOS_USB_H */ - -/** - * @} - * @} - */ diff --git a/flight/Bootloaders/OpenPilot/inc/pios_usb_board_data.h b/flight/Bootloaders/OpenPilot/inc/pios_usb_board_data.h new file mode 100644 index 000000000..ca9c948b0 --- /dev/null +++ b/flight/Bootloaders/OpenPilot/inc/pios_usb_board_data.h @@ -0,0 +1,51 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB_BOARD Board specific USB definitions + * @brief Board specific USB definitions + * @{ + * + * @file pios_usb_board_data.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Board specific USB definitions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_USB_BOARD_DATA_H +#define PIOS_USB_BOARD_DATA_H + +#define PIOS_USB_BOARD_HID_DATA_LENGTH 64 + +#define PIOS_USB_BOARD_EP_NUM 2 + +#include "pios_usb_defs.h" /* struct usb_* */ + +#define PIOS_USB_BOARD_PRODUCT_ID USB_PRODUCT_ID_OPENPILOT_MAIN +#define PIOS_USB_BOARD_DEVICE_VER USB_OP_DEVICE_VER(USB_OP_BOARD_ID_OPENPILOT_MAIN, USB_OP_BOARD_MODE_BL) + +/* + * The bootloader uses a simplified report structure + * BL: ... + * FW: ... + * This define changes the behaviour in pios_usb_hid.c + */ +#define PIOS_USB_BOARD_BL_HID_HAS_NO_LENGTH_BYTE + +#endif /* PIOS_USB_BOARD_DATA_H */ diff --git a/flight/Bootloaders/OpenPilot/main.c b/flight/Bootloaders/OpenPilot/main.c index 8e15952ea..3a06c9751 100644 --- a/flight/Bootloaders/OpenPilot/main.c +++ b/flight/Bootloaders/OpenPilot/main.c @@ -35,6 +35,7 @@ #include "pios_iap.h" #include "ssp.h" #include "fifo_buffer.h" +#include "pios_com_msg.h" /* Prototype of PIOS_Board_Init() function */ extern void PIOS_Board_Init(void); extern void FLASH_Download(); @@ -90,7 +91,7 @@ uint8_t JumpToApp = FALSE; uint8_t GO_dfu = FALSE; uint8_t USB_connected = FALSE; uint8_t User_DFU_request = FALSE; -static uint8_t mReceive_Buffer[64]; +static uint8_t mReceive_Buffer[63]; /* Private function prototypes -----------------------------------------------*/ uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count); uint8_t processRX(); @@ -101,10 +102,6 @@ uint32_t sspTimeSource(); #define RED LED2 #define LED_PWM_TIMER TIM6 int main() { - /* NOTE: Do NOT modify the following start-up sequence */ - /* Any new initialization functions should be added in OpenPilotInit() */ - - /* Brings up System using CMSIS functions, enables the LEDs. */ PIOS_SYS_Init(); if (BSL_HOLD_STATE == 0) USB_connected = TRUE; @@ -227,7 +224,6 @@ void jump_to_app() { RCC_APB1PeriphResetCmd(0xffffffff, DISABLE); _SetCNTR(0); // clear interrupt mask _SetISTR(0); // clear all requests - JumpAddress = *(__IO uint32_t*) (bdinfo->fw_base + 4); Jump_To_Application = (pFunction) JumpAddress; /* Initialize user application's Stack Pointer */ @@ -249,10 +245,8 @@ uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count) { uint8_t processRX() { if (ProgPort == Usb) { - while (PIOS_COM_ReceiveBufferUsed(PIOS_COM_TELEM_USB) >= 63) { - if (PIOS_COM_ReceiveBuffer(PIOS_COM_TELEM_USB, mReceive_Buffer, 63, 0) == 63) { - processComand(mReceive_Buffer); - } + if (PIOS_COM_MSG_Receive(PIOS_COM_TELEM_USB, mReceive_Buffer, sizeof(mReceive_Buffer))) { + processComand(mReceive_Buffer); } } else if (ProgPort == Serial) { @@ -277,15 +271,12 @@ void SSP_CallBack(uint8_t *buf, uint16_t len) { fifoBuf_putData(&ssp_buffer, buf, len); } int16_t SSP_SerialRead(void) { - if (PIOS_COM_ReceiveBufferUsed(PIOS_COM_TELEM_RF) > 0) { - uint8_t byte; - if (PIOS_COM_ReceiveBuffer(PIOS_COM_TELEM_RF, &byte, 1, 0) == 1) { - return byte; - } else { - return -1; - } - } else + uint8_t byte; + if (PIOS_COM_ReceiveBuffer(PIOS_COM_TELEM_RF, &byte, 1, 0) == 1) { + return byte; + } else { return -1; + } } void SSP_SerialWrite(uint8_t value) { PIOS_COM_SendChar(PIOS_COM_TELEM_RF, value); diff --git a/flight/Bootloaders/OpenPilot/op_dfu.c b/flight/Bootloaders/OpenPilot/op_dfu.c index bc62fff6c..ef30e4897 100644 --- a/flight/Bootloaders/OpenPilot/op_dfu.c +++ b/flight/Bootloaders/OpenPilot/op_dfu.c @@ -30,13 +30,10 @@ #include "pios.h" #include "op_dfu.h" #include "pios_bl_helper.h" +#include "pios_com_msg.h" #include #include "pios_opahrs.h" #include "ssp.h" -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ //programmable devices Device devicesTable[10]; uint8_t numberOfDevices = 0; @@ -222,7 +219,7 @@ void processComand(uint8_t *xReceive_Buffer) { } } if (result != 1) { - DeviceState = Last_operation_failed;//ok + DeviceState = Last_operation_failed; Aditionals = (uint32_t) Command; } else { @@ -299,7 +296,6 @@ void processComand(uint8_t *xReceive_Buffer) { ++Next_Packet; } else { - DeviceState = wrong_packet_received; Aditionals = Count; } @@ -353,10 +349,18 @@ void processComand(uint8_t *xReceive_Buffer) { DeviceState = failed_jump; break; } else { + if (Data == 0x5AFE) { + /* Force board into safe mode */ + PIOS_IAP_WriteBootCount(0xFFFF); + } FLASH_Lock(); JumpToApp = 1; } } else { + if (Data == 0x5AFE) { + /* Force board into safe mode */ + PIOS_IAP_WriteBootCount(0xFFFF); + } FLASH_Lock(); JumpToApp = 1; } @@ -384,7 +388,6 @@ void processComand(uint8_t *xReceive_Buffer) { DeviceState = too_few_packets; } } - break; case Download_Req: #ifdef DEBUG_SSP @@ -508,6 +511,7 @@ uint32_t baseOfAdressType(DFUTransfer type) { return currentDevice.startOfUserCode + currentDevice.sizeOfCode; break; default: + return 0; } } @@ -550,11 +554,7 @@ uint32_t CalcFirmCRC() { } void sendData(uint8_t * buf, uint16_t size) { if (ProgPort == Usb) { - - PIOS_COM_SendBuffer(PIOS_COM_TELEM_USB, buf, size); - if (DeviceState == downloading) - PIOS_DELAY_WaitmS(10); - + PIOS_COM_MSG_Send(PIOS_COM_TELEM_USB, buf, size); } else if (ProgPort == Serial) { ssp_SendData(&ssp_port, buf, size); } diff --git a/flight/Bootloaders/OpenPilot/pios_board.c b/flight/Bootloaders/OpenPilot/pios_board.c index 5defbb626..d1ba74d8b 100644 --- a/flight/Bootloaders/OpenPilot/pios_board.c +++ b/flight/Bootloaders/OpenPilot/pios_board.c @@ -184,12 +184,6 @@ const struct pios_usart_cfg pios_usart_telem_cfg = { #include "pios_com_priv.h" -#define PIOS_COM_TELEM_USB_RX_BUF_LEN 192 -#define PIOS_COM_TELEM_USB_TX_BUF_LEN 192 - -static uint8_t pios_com_telem_usb_rx_buffer[PIOS_COM_TELEM_USB_RX_BUF_LEN]; -static uint8_t pios_com_telem_usb_tx_buffer[PIOS_COM_TELEM_USB_TX_BUF_LEN]; - #define PIOS_COM_TELEM_RF_RX_BUF_LEN 192 #define PIOS_COM_TELEM_RF_TX_BUF_LEN 192 @@ -198,10 +192,20 @@ static uint8_t pios_com_telem_rf_tx_buffer[PIOS_COM_TELEM_RF_TX_BUF_LEN]; #endif /* PIOS_INCLUDE_COM */ -#if defined(PIOS_INCLUDE_USB_HID) -#include "pios_usb_hid_priv.h" +// *********************************************************************************** -static const struct pios_usb_hid_cfg pios_usb_hid_main_cfg = { +#if defined(PIOS_INCLUDE_COM_MSG) + +#include + +#endif /* PIOS_INCLUDE_COM_MSG */ + +// *********************************************************************************** + +#if defined(PIOS_INCLUDE_USB) +#include "pios_usb_priv.h" + +static const struct pios_usb_cfg pios_usb_main_cfg = { .irq = { .init = { .NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn, @@ -211,9 +215,22 @@ static const struct pios_usb_hid_cfg pios_usb_hid_main_cfg = { }, }, }; -#endif /* PIOS_INCLUDE_USB_HID */ -extern const struct pios_com_driver pios_usb_com_driver; +#include "pios_usb_board_data_priv.h" +#include "pios_usb_desc_hid_only_priv.h" + +#endif /* PIOS_INCLUDE_USB */ + +#if defined(PIOS_INCLUDE_USB_HID) +#include + +const struct pios_usb_hid_cfg pios_usb_hid_cfg = { + .data_if = 0, + .data_rx_ep = 1, + .data_tx_ep = 1, +}; + +#endif /* PIOS_INCLUDE_USB_HID */ uint32_t pios_com_telem_rf_id; uint32_t pios_com_telem_usb_id; @@ -256,17 +273,28 @@ void PIOS_Board_Init(void) { PIOS_GPIO_Init(); -#if defined(PIOS_INCLUDE_USB_HID) - uint32_t pios_usb_hid_id; - PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_main_cfg); -#if defined(PIOS_INCLUDE_COM) - if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_com_driver, pios_usb_hid_id, - pios_com_telem_usb_rx_buffer, sizeof(pios_com_telem_usb_rx_buffer), - pios_com_telem_usb_tx_buffer, sizeof(pios_com_telem_usb_tx_buffer))) { +#if defined(PIOS_INCLUDE_USB) + /* Initialize board specific USB data */ + PIOS_USB_BOARD_DATA_Init(); + + /* Activate the HID-only USB configuration */ + PIOS_USB_DESC_HID_ONLY_Init(); + + uint32_t pios_usb_id; + if (PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg)) { PIOS_Assert(0); } -#endif /* PIOS_INCLUDE_COM */ -#endif /* PIOS_INCLUDE_USB_HID */ +#if defined(PIOS_INCLUDE_USB_HID) && defined(PIOS_INCLUDE_COM_MSG) + uint32_t pios_usb_hid_id; + if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) { + PIOS_Assert(0); + } + if (PIOS_COM_MSG_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id)) { + PIOS_Assert(0); + } +#endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_COM_MSG */ + +#endif /* PIOS_INCLUDE_USB */ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_CRC, ENABLE);//TODO Tirar diff --git a/flight/Bootloaders/OpenPilot/pios_usb_board_data.c b/flight/Bootloaders/OpenPilot/pios_usb_board_data.c new file mode 100644 index 000000000..b73419ba4 --- /dev/null +++ b/flight/Bootloaders/OpenPilot/pios_usb_board_data.c @@ -0,0 +1,119 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB_BOARD Board specific USB definitions + * @brief Board specific USB definitions + * @{ + * + * @file pios_usb_board_data.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Board specific USB definitions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "pios_usb_board_data.h" /* struct usb_*, USB_* */ +#include "pios_sys.h" /* PIOS_SYS_SerialNumberGet */ +#include "pios_usbhook.h" /* PIOS_USBHOOK_* */ + +static const uint8_t usb_product_id[20] = { + sizeof(usb_product_id), + USB_DESC_TYPE_STRING, + 'O', 0, + 'p', 0, + 'e', 0, + 'n', 0, + 'P', 0, + 'i', 0, + 'l', 0, + 'o', 0, + 't', 0, +}; + +static uint8_t usb_serial_number[52] = { + sizeof(usb_serial_number), + USB_DESC_TYPE_STRING, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0 +}; + +static const struct usb_string_langid usb_lang_id = { + .bLength = sizeof(usb_lang_id), + .bDescriptorType = USB_DESC_TYPE_STRING, + .bLangID = htousbs(USB_LANGID_ENGLISH_UK), +}; + +static const uint8_t usb_vendor_id[28] = { + sizeof(usb_vendor_id), + USB_DESC_TYPE_STRING, + 'o', 0, + 'p', 0, + 'e', 0, + 'n', 0, + 'p', 0, + 'i', 0, + 'l', 0, + 'o', 0, + 't', 0, + '.', 0, + 'o', 0, + 'r', 0, + 'g', 0 +}; + +int32_t PIOS_USB_BOARD_DATA_Init(void) +{ + /* Load device serial number into serial number string */ + uint8_t sn[25]; + PIOS_SYS_SerialNumberGet((char *)sn); + for (uint8_t i = 0; sn[i] != '\0' && (2 * i) < usb_serial_number[0]; i++) { + usb_serial_number[2 + 2 * i] = sn[i]; + } + + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_PRODUCT, (uint8_t *)&usb_product_id, sizeof(usb_product_id)); + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_SERIAL, (uint8_t *)&usb_serial_number, sizeof(usb_serial_number)); + + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_LANG, (uint8_t *)&usb_lang_id, sizeof(usb_lang_id)); + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_VENDOR, (uint8_t *)&usb_vendor_id, sizeof(usb_vendor_id)); + + return 0; +} diff --git a/flight/Bootloaders/PipXtreme/Makefile b/flight/Bootloaders/PipXtreme/Makefile index deb33d3a4..5a788e7e6 100644 --- a/flight/Bootloaders/PipXtreme/Makefile +++ b/flight/Bootloaders/PipXtreme/Makefile @@ -107,15 +107,19 @@ SRC += $(PIOSSTM32F10X)/pios_iap.c SRC += $(PIOSSTM32F10X)/pios_bl_helper.c # PIOS USB related files (seperated to make code maintenance more easy) +SRC += $(PIOSSTM32F10X)/pios_usb.c +SRC += $(PIOSSTM32F10X)/pios_usbhook.c SRC += $(PIOSSTM32F10X)/pios_usb_hid.c -SRC += $(PIOSSTM32F10X)/pios_usb_hid_desc.c SRC += $(PIOSSTM32F10X)/pios_usb_hid_istr.c -SRC += $(PIOSSTM32F10X)/pios_usb_hid_prop.c SRC += $(PIOSSTM32F10X)/pios_usb_hid_pwr.c +SRC += $(OPSYSTEM)/pios_usb_board_data.c +SRC += $(PIOSCOMMON)/pios_usb_desc_hid_only.c ## PIOS Hardware (Common) SRC += $(PIOSCOMMON)/pios_board_info.c -SRC += $(PIOSCOMMON)/pios_com.c +SRC += $(PIOSCOMMON)/pios_com_msg.c +SRC += $(PIOSCOMMON)/pios_bl_helper.c +SRC += $(PIOSCOMMON)/pios_iap.c SRC += $(PIOSCOMMON)/printf-stdarg.c ## Libraries for flight calculations @@ -285,7 +289,7 @@ CSTANDARD = -std=gnu99 # Flags for C and C++ (arm-elf-gcc/arm-elf-g++) ifeq ($(DEBUG),YES) -CFLAGS = -DDEBUG +CFLAGS += -DDEBUG endif CFLAGS += -g$(DEBUGF) diff --git a/flight/Bootloaders/PipXtreme/inc/pios_config.h b/flight/Bootloaders/PipXtreme/inc/pios_config.h index 799847992..1b1b9c2bc 100644 --- a/flight/Bootloaders/PipXtreme/inc/pios_config.h +++ b/flight/Bootloaders/PipXtreme/inc/pios_config.h @@ -31,16 +31,16 @@ #define PIOS_CONFIG_H #define PIOS_INCLUDE_BL_HELPER #define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT -#define USB_HID /* Enable/Disable PiOS Modules */ #define PIOS_INCLUDE_DELAY #define PIOS_INCLUDE_IRQ #define PIOS_INCLUDE_LED #define PIOS_INCLUDE_SYS +#define PIOS_INCLUDE_USB #define PIOS_INCLUDE_USB_HID -#define PIOS_INCLUDE_COM +#define PIOS_INCLUDE_COM_MSG #define PIOS_INCLUDE_GPIO -//#define DEBUG_SSP +#define PIOS_INCLUDE_IAP /* Defaults for Logging */ #define LOG_FILENAME "PIOS.LOG" diff --git a/flight/Bootloaders/PipXtreme/inc/pios_usb.h b/flight/Bootloaders/PipXtreme/inc/pios_usb.h deleted file mode 100644 index 1b7688217..000000000 --- a/flight/Bootloaders/PipXtreme/inc/pios_usb.h +++ /dev/null @@ -1,85 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_USB USB Functions - * @brief PIOS USB interface code - * @{ - * - * @file pios_usb.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) - * @brief USB 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_USB_H -#define PIOS_USB_H - -/* Local defines */ -/* Following settings allow to customise the USB device descriptor */ -#ifndef PIOS_USB_VENDOR_ID -#define PIOS_USB_VENDOR_ID 0x20A0 -#endif - -#ifndef PIOS_USB_VENDOR_STR -#define PIOS_USB_VENDOR_STR "openpilot.org" -#endif - -#ifndef PIOS_USB_PRODUCT_STR -#define PIOS_USB_PRODUCT_STR "PipXtreme" -#endif - -#ifndef PIOS_USB_PRODUCT_ID -#define PIOS_USB_PRODUCT_ID 0x415C -#endif - -#ifndef PIOS_USB_VERSION_ID -#define PIOS_USB_VERSION_ID 0x0301 /* PipXtreme (03) Bootloader (01) */ -#endif - -/* Internal defines which are used by PIOS USB HID (don't touch) */ -#define PIOS_USB_EP_NUM 2 - -/* Buffer table base address */ -#define PIOS_USB_BTABLE_ADDRESS 0x000 - -/* EP0 rx/tx buffer base address */ -#define PIOS_USB_ENDP0_RXADDR 0x040 -#define PIOS_USB_ENDP0_TXADDR 0x080 - -/* EP1 Rx/Tx buffer base address for HID driver */ -#define PIOS_USB_ENDP1_TXADDR 0x0C0 -#define PIOS_USB_ENDP1_RXADDR 0x100 - -/* Global Variables */ -extern void (*pEpInt_IN[7])(void); -extern void (*pEpInt_OUT[7])(void); - -/* Public Functions */ -extern int32_t PIOS_USB_Init(uint32_t mode); -extern int32_t PIOS_USB_IsInitialized(void); -extern int32_t PIOS_USB_CableConnected(void); - -#endif /* PIOS_USB_H */ - -/** - * @} - * @} - */ diff --git a/flight/Bootloaders/PipXtreme/inc/pios_usb_board_data.h b/flight/Bootloaders/PipXtreme/inc/pios_usb_board_data.h new file mode 100644 index 000000000..2e35f2fa4 --- /dev/null +++ b/flight/Bootloaders/PipXtreme/inc/pios_usb_board_data.h @@ -0,0 +1,51 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB_BOARD Board specific USB definitions + * @brief Board specific USB definitions + * @{ + * + * @file pios_usb_board_data.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Board specific USB definitions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_USB_BOARD_DATA_H +#define PIOS_USB_BOARD_DATA_H + +#define PIOS_USB_BOARD_HID_DATA_LENGTH 64 + +#define PIOS_USB_BOARD_EP_NUM 2 + +#include "pios_usb_defs.h" /* struct usb_* */ + +#define PIOS_USB_BOARD_PRODUCT_ID USB_PRODUCT_ID_PIPXTREME +#define PIOS_USB_BOARD_DEVICE_VER USB_OP_DEVICE_VER(USB_OP_BOARD_ID_PIPXTREME, USB_OP_BOARD_MODE_BL) + +/* + * The bootloader uses a simplified report structure + * BL: ... + * FW: ... + * This define changes the behaviour in pios_usb_hid.c + */ +#define PIOS_USB_BOARD_BL_HID_HAS_NO_LENGTH_BYTE + +#endif /* PIOS_USB_BOARD_DATA_H */ diff --git a/flight/Bootloaders/PipXtreme/main.c b/flight/Bootloaders/PipXtreme/main.c index 3f1c4bd54..602193f5c 100644 --- a/flight/Bootloaders/PipXtreme/main.c +++ b/flight/Bootloaders/PipXtreme/main.c @@ -32,6 +32,7 @@ #include "usb_lib.h" #include "pios_iap.h" #include "fifo_buffer.h" +#include "pios_com_msg.h" /* Prototype of PIOS_Board_Init() function */ extern void PIOS_Board_Init(void); extern void FLASH_Download(); @@ -62,7 +63,7 @@ uint8_t JumpToApp = FALSE; uint8_t GO_dfu = FALSE; uint8_t USB_connected = FALSE; uint8_t User_DFU_request = FALSE; -static uint8_t mReceive_Buffer[64]; +static uint8_t mReceive_Buffer[63]; /* Private function prototypes -----------------------------------------------*/ uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count); uint8_t processRX(); @@ -71,10 +72,6 @@ void jump_to_app(); #define BLUE LED1 #define RED LED4 int main() { - /* NOTE: Do NOT modify the following start-up sequence */ - /* Any new initialization functions should be added in OpenPilotInit() */ - - /* Brings up System using CMSIS functions, enables the LEDs. */ PIOS_SYS_Init(); if (BSL_HOLD_STATE == 0) USB_connected = TRUE; @@ -181,7 +178,6 @@ void jump_to_app() { RCC_APB1PeriphResetCmd(0xffffffff, DISABLE); _SetCNTR(0); // clear interrupt mask _SetISTR(0); // clear all requests - JumpAddress = *(__IO uint32_t*) (bdinfo->fw_base + 4); Jump_To_Application = (pFunction) JumpAddress; /* Initialize user application's Stack Pointer */ @@ -204,10 +200,8 @@ uint32_t LedPWM(uint32_t pwm_period, uint32_t pwm_sweep_steps, uint32_t count) { } uint8_t processRX() { - while (PIOS_COM_ReceiveBufferUsed(PIOS_COM_TELEM_USB) >= 63) { - if (PIOS_COM_ReceiveBuffer(PIOS_COM_TELEM_USB, mReceive_Buffer, 63, 0) == 63) { - processComand(mReceive_Buffer); - } + if (PIOS_COM_MSG_Receive(PIOS_COM_TELEM_USB, mReceive_Buffer, sizeof(mReceive_Buffer))) { + processComand(mReceive_Buffer); } return TRUE; } diff --git a/flight/Bootloaders/PipXtreme/op_dfu.c b/flight/Bootloaders/PipXtreme/op_dfu.c index 770ce8237..249e3d320 100644 --- a/flight/Bootloaders/PipXtreme/op_dfu.c +++ b/flight/Bootloaders/PipXtreme/op_dfu.c @@ -30,11 +30,8 @@ #include "pios.h" #include "op_dfu.h" #include "pios_bl_helper.h" +#include "pios_com_msg.h" #include -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ //programmable devices Device devicesTable[10]; uint8_t numberOfDevices = 0; @@ -102,33 +99,9 @@ void DataDownload(DownloadAction action) { currentProgrammingDestination)) { DeviceState = Last_operation_failed; } - /* - switch (currentProgrammingDestination) { - case Remote_flash_via_spi: - if (downType == Descript) { - SendBuffer[6 + (x * 4)] - = spi_dev_desc[(uint8_t) partoffset]; - SendBuffer[7 + (x * 4)] = spi_dev_desc[(uint8_t) partoffset - + 1]; - SendBuffer[8 + (x * 4)] = spi_dev_desc[(uint8_t) partoffset - + 2]; - SendBuffer[9 + (x * 4)] = spi_dev_desc[(uint8_t) partoffset - + 3]; - } - break; - case Self_flash: - SendBuffer[6 + (x * 4)] = *PIOS_BL_HELPER_FLASH_If_Read(offset); - SendBuffer[7 + (x * 4)] = *PIOS_BL_HELPER_FLASH_If_Read(offset + 1); - SendBuffer[8 + (x * 4)] = *PIOS_BL_HELPER_FLASH_If_Read(offset + 2); - SendBuffer[9 + (x * 4)] = *PIOS_BL_HELPER_FLASH_If_Read(offset + 3); - break; - } - */ } - //PIOS USB_SIL_Write(EP1_IN, (uint8_t*) SendBuffer, 64); downPacketCurrent = downPacketCurrent + 1; if (downPacketCurrent > downPacketTotal - 1) { - // STM_EVAL_LEDOn(LED2); DeviceState = Last_operation_Success; Aditionals = (uint32_t) Download; } @@ -168,7 +141,7 @@ void processComand(uint8_t *xReceive_Buffer) { case EnterDFU: if (((DeviceState == BLidle) && (Data0 < numberOfDevices)) || (DeviceState == DFUidle)) { - if (Data0 > 0)//PORQUE??? + if (Data0 > 0) OPDfuIni(TRUE); DeviceState = DFUidle; currentProgrammingDestination = devicesTable[Data0].programmingType; @@ -225,7 +198,7 @@ void processComand(uint8_t *xReceive_Buffer) { } } if (result != 1) { - DeviceState = Last_operation_failed;//ok + DeviceState = Last_operation_failed; Aditionals = (uint32_t) Command; } else { @@ -276,11 +249,9 @@ void processComand(uint8_t *xReceive_Buffer) { ++Next_Packet; } else { - DeviceState = wrong_packet_received; Aditionals = Count; } - // FLASH_ProgramWord(MemLocations[TransferType]+4,++Next_Packet);//+Count,Data); } else { DeviceState = Last_operation_failed; Aditionals = (uint32_t) Command; @@ -322,9 +293,12 @@ void processComand(uint8_t *xReceive_Buffer) { Buffer[15] = devicesTable[Data0 - 1].devID; } sendData(Buffer + 1, 63); - //PIOS_COM_SendBuffer(PIOS_COM_TELEM_USB, Buffer + 1, 63);//FIX+1 break; case JumpFW: + if (Data == 0x5AFE) { + /* Force board into safe mode */ + PIOS_IAP_WriteBootCount(0xFFFF); + } FLASH_Lock(); JumpToApp = 1; break; @@ -351,7 +325,6 @@ void processComand(uint8_t *xReceive_Buffer) { DeviceState = too_few_packets; } } - break; case Download_Req: #ifdef DEBUG_SSP @@ -474,9 +447,7 @@ uint32_t CalcFirmCRC() { } void sendData(uint8_t * buf, uint16_t size) { - PIOS_COM_SendBuffer(PIOS_COM_TELEM_USB, buf, size); - if (DeviceState == downloading) - PIOS_DELAY_WaitmS(10); + PIOS_COM_MSG_Send(PIOS_COM_TELEM_USB, buf, size); } bool flash_read(uint8_t * buffer, uint32_t adr, DFUProgType type) { diff --git a/flight/Bootloaders/PipXtreme/pios_board.c b/flight/Bootloaders/PipXtreme/pios_board.c index 83f0f407a..a70537fcc 100644 --- a/flight/Bootloaders/PipXtreme/pios_board.c +++ b/flight/Bootloaders/PipXtreme/pios_board.c @@ -27,24 +27,18 @@ // *********************************************************************************** -#if defined(PIOS_INCLUDE_COM) +#if defined(PIOS_INCLUDE_COM_MSG) -#include +#include -#define PIOS_COM_TELEM_USB_RX_BUF_LEN 192 -#define PIOS_COM_TELEM_USB_TX_BUF_LEN 192 - -static uint8_t pios_com_telem_usb_rx_buffer[PIOS_COM_TELEM_USB_RX_BUF_LEN]; -static uint8_t pios_com_telem_usb_tx_buffer[PIOS_COM_TELEM_USB_TX_BUF_LEN]; - -#endif /* PIOS_INCLUDE_COM */ +#endif /* PIOS_INCLUDE_COM_MSG */ // *********************************************************************************** -#if defined(PIOS_INCLUDE_USB_HID) -#include "pios_usb_hid_priv.h" +#if defined(PIOS_INCLUDE_USB) +#include "pios_usb_priv.h" -static const struct pios_usb_hid_cfg pios_usb_hid_main_cfg = { +static const struct pios_usb_cfg pios_usb_main_cfg = { .irq = { .init = { .NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn, @@ -54,9 +48,22 @@ static const struct pios_usb_hid_cfg pios_usb_hid_main_cfg = { }, }, }; -#endif /* PIOS_INCLUDE_USB_HID */ -extern const struct pios_com_driver pios_usb_com_driver; +#include "pios_usb_board_data_priv.h" +#include "pios_usb_desc_hid_only_priv.h" + +#endif /* PIOS_INCLUDE_USB */ + +#if defined(PIOS_INCLUDE_USB_HID) +#include + +const struct pios_usb_hid_cfg pios_usb_hid_cfg = { + .data_if = 0, + .data_rx_ep = 1, + .data_tx_ep = 1, +}; + +#endif /* PIOS_INCLUDE_USB_HID */ uint32_t pios_com_telem_usb_id; @@ -83,17 +90,28 @@ void PIOS_Board_Init(void) { /* Initialize the PiOS library */ PIOS_GPIO_Init(); -#if defined(PIOS_INCLUDE_USB_HID) - uint32_t pios_usb_hid_id; - PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_main_cfg); -#if defined(PIOS_INCLUDE_COM) - if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_com_driver, pios_usb_hid_id, - pios_com_telem_usb_rx_buffer, sizeof(pios_com_telem_usb_rx_buffer), - pios_com_telem_usb_tx_buffer, sizeof(pios_com_telem_usb_tx_buffer))) { +#if defined(PIOS_INCLUDE_USB) + /* Initialize board specific USB data */ + PIOS_USB_BOARD_DATA_Init(); + + /* Activate the HID-only USB configuration */ + PIOS_USB_DESC_HID_ONLY_Init(); + + uint32_t pios_usb_id; + if (PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg)) { PIOS_Assert(0); } -#endif /* PIOS_INCLUDE_COM */ -#endif /* PIOS_INCLUDE_USB_HID */ +#if defined(PIOS_INCLUDE_USB_HID) && defined(PIOS_INCLUDE_COM_MSG) + uint32_t pios_usb_hid_id; + if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) { + PIOS_Assert(0); + } + if (PIOS_COM_MSG_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id)) { + PIOS_Assert(0); + } +#endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_COM_MSG */ + +#endif /* PIOS_INCLUDE_USB */ RCC_AHBPeriphClockCmd(RCC_AHBPeriph_CRC, ENABLE);//TODO Tirar diff --git a/flight/Bootloaders/PipXtreme/pios_usb_board_data.c b/flight/Bootloaders/PipXtreme/pios_usb_board_data.c new file mode 100644 index 000000000..3e41e5ac9 --- /dev/null +++ b/flight/Bootloaders/PipXtreme/pios_usb_board_data.c @@ -0,0 +1,119 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB_BOARD Board specific USB definitions + * @brief Board specific USB definitions + * @{ + * + * @file pios_usb_board_data.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Board specific USB definitions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "pios_usb_board_data.h" /* struct usb_*, USB_* */ +#include "pios_sys.h" /* PIOS_SYS_SerialNumberGet */ +#include "pios_usbhook.h" /* PIOS_USBHOOK_* */ + +static const uint8_t usb_product_id[20] = { + sizeof(usb_product_id), + USB_DESC_TYPE_STRING, + 'P', 0, + 'i', 0, + 'p', 0, + 'X', 0, + 't', 0, + 'r', 0, + 'e', 0, + 'm', 0, + 'e', 0, +}; + +static uint8_t usb_serial_number[52] = { + sizeof(usb_serial_number), + USB_DESC_TYPE_STRING, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0 +}; + +static const struct usb_string_langid usb_lang_id = { + .bLength = sizeof(usb_lang_id), + .bDescriptorType = USB_DESC_TYPE_STRING, + .bLangID = htousbs(USB_LANGID_ENGLISH_UK), +}; + +static const uint8_t usb_vendor_id[28] = { + sizeof(usb_vendor_id), + USB_DESC_TYPE_STRING, + 'o', 0, + 'p', 0, + 'e', 0, + 'n', 0, + 'p', 0, + 'i', 0, + 'l', 0, + 'o', 0, + 't', 0, + '.', 0, + 'o', 0, + 'r', 0, + 'g', 0 +}; + +int32_t PIOS_USB_BOARD_DATA_Init(void) +{ + /* Load device serial number into serial number string */ + uint8_t sn[25]; + PIOS_SYS_SerialNumberGet((char *)sn); + for (uint8_t i = 0; sn[i] != '\0' && (2 * i) < usb_serial_number[0]; i++) { + usb_serial_number[2 + 2 * i] = sn[i]; + } + + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_PRODUCT, (uint8_t *)&usb_product_id, sizeof(usb_product_id)); + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_SERIAL, (uint8_t *)&usb_serial_number, sizeof(usb_serial_number)); + + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_LANG, (uint8_t *)&usb_lang_id, sizeof(usb_lang_id)); + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_VENDOR, (uint8_t *)&usb_vendor_id, sizeof(usb_vendor_id)); + + return 0; +} diff --git a/flight/Bootloaders/Revolution/inc/pios_config.h b/flight/Bootloaders/Revolution/inc/pios_config.h index 578a01445..68fc87e78 100644 --- a/flight/Bootloaders/Revolution/inc/pios_config.h +++ b/flight/Bootloaders/Revolution/inc/pios_config.h @@ -1,39 +1,39 @@ -/** - ****************************************************************************** - * - * @file pios_config.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief PiOS configuration header. - * - Central compile time config for the project. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_CONFIG_H -#define PIOS_CONFIG_H - -/* Enable/Disable PiOS Modules */ -#define PIOS_INCLUDE_DELAY -#define PIOS_INCLUDE_IRQ -#define PIOS_INCLUDE_LED -#define PIOS_INCLUDE_SPI -#define PIOS_INCLUDE_SYS -//#define PIOS_INCLUDE_BL_HELPER -//#define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT - -#endif /* PIOS_CONFIG_H */ +/** + ****************************************************************************** + * + * @file pios_config.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief PiOS configuration header. + * - Central compile time config for the project. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_CONFIG_H +#define PIOS_CONFIG_H + +/* Enable/Disable PiOS Modules */ +#define PIOS_INCLUDE_DELAY +#define PIOS_INCLUDE_IRQ +#define PIOS_INCLUDE_LED +#define PIOS_INCLUDE_SPI +#define PIOS_INCLUDE_SYS +//#define PIOS_INCLUDE_BL_HELPER +//#define PIOS_INCLUDE_BL_HELPER_WRITE_SUPPORT + +#endif /* PIOS_CONFIG_H */ diff --git a/flight/CopterControl/Makefile b/flight/CopterControl/Makefile index 75f4958ce..b657ddfcd 100644 --- a/flight/CopterControl/Makefile +++ b/flight/CopterControl/Makefile @@ -50,7 +50,7 @@ ENABLE_AUX_UART ?= NO USE_GPS ?= YES -USE_I2C ?= NO +USE_I2C ?= YES # Set to YES when using Code Sourcery toolchain CODE_SOURCERY ?= YES @@ -65,11 +65,15 @@ endif FLASH_TOOL = OPENOCD # List of modules to include -OPTMODULES = CameraStab +OPTMODULES = CameraStab ComUsbBridge Altitude ifeq ($(USE_GPS), YES) OPTMODULES += GPS endif +ifeq ($(TEST_FAULTS), YES) +OPTMODULES += Fault +endif + MODULES = Attitude Stabilization Actuator ManualControl FirmwareIAP # Telemetry must be last to grab the optional modules (why?) MODULES += Telemetry @@ -132,11 +136,9 @@ SRC += ${OPMODULEDIR}/System/systemmod.c SRC += $(OPSYSTEM)/coptercontrol.c SRC += $(OPSYSTEM)/pios_board.c SRC += $(OPSYSTEM)/alarms.c -SRC += $(OPSYSTEM)/taskmonitor.c SRC += $(OPUAVTALK)/uavtalk.c SRC += $(OPUAVOBJ)/uavobjectmanager.c SRC += $(OPUAVOBJ)/eventdispatcher.c -SRC += $(OPSYSTEM)/pios_usb_hid_desc.c else ## TESTCODE SRC += $(OPTESTS)/test_common.c @@ -151,6 +153,7 @@ SRC += $(OPUAVSYNTHDIR)/accessorydesired.c SRC += $(OPUAVSYNTHDIR)/objectpersistence.c SRC += $(OPUAVSYNTHDIR)/gcstelemetrystats.c SRC += $(OPUAVSYNTHDIR)/flighttelemetrystats.c +SRC += $(OPUAVSYNTHDIR)/faultsettings.c SRC += $(OPUAVSYNTHDIR)/flightstatus.c SRC += $(OPUAVSYNTHDIR)/systemstats.c SRC += $(OPUAVSYNTHDIR)/systemalarms.c @@ -178,6 +181,7 @@ SRC += $(OPUAVSYNTHDIR)/receiveractivity.c SRC += $(OPUAVSYNTHDIR)/taskinfo.c SRC += $(OPUAVSYNTHDIR)/mixerstatus.c SRC += $(OPUAVSYNTHDIR)/ratedesired.c +SRC += $(OPUAVSYNTHDIR)/baroaltitude.c endif @@ -204,11 +208,16 @@ SRC += $(PIOSSTM32F10X)/pios_iap.c SRC += $(PIOSSTM32F10X)/pios_tim.c SRC += $(PIOSSTM32F10X)/pios_bl_helper.c -# PIOS USB related files (seperated to make code maintenance more easy) +# PIOS USB related files (separated to make code maintenance more easy) +SRC += $(PIOSSTM32F10X)/pios_usb.c +SRC += $(PIOSSTM32F10X)/pios_usbhook.c SRC += $(PIOSSTM32F10X)/pios_usb_hid.c +SRC += $(PIOSSTM32F10X)/pios_usb_cdc.c SRC += $(PIOSSTM32F10X)/pios_usb_hid_istr.c -SRC += $(PIOSSTM32F10X)/pios_usb_hid_prop.c SRC += $(PIOSSTM32F10X)/pios_usb_hid_pwr.c +SRC += $(OPSYSTEM)/pios_usb_board_data.c +SRC += $(PIOSCOMMON)/pios_usb_desc_hid_cdc.c +SRC += $(PIOSCOMMON)/pios_usb_desc_hid_only.c ## PIOS Hardware (Common) SRC += $(PIOSCOMMON)/pios_crc.c @@ -217,12 +226,16 @@ SRC += $(PIOSCOMMON)/pios_flash_w25x.c SRC += $(PIOSCOMMON)/pios_adxl345.c SRC += $(PIOSCOMMON)/pios_com.c SRC += $(PIOSCOMMON)/pios_i2c_esc.c +SRC += $(PIOSCOMMON)/pios_bmp085.c +SRC += $(PIOSCOMMON)/pios_iap.c +SRC += $(PIOSCOMMON)/pios_bl_helper.c SRC += $(PIOSCOMMON)/pios_rcvr.c SRC += $(PIOSCOMMON)/pios_gcsrcvr.c SRC += $(PIOSCOMMON)/printf-stdarg.c ## Libraries for flight calculations SRC += $(FLIGHTLIB)/fifo_buffer.c SRC += $(FLIGHTLIB)/CoordinateConversions.c +SRC += $(FLIGHTLIB)/taskmonitor.c ## CMSIS for STM32 SRC += $(CMSISDIR)/core_cm3.c @@ -400,6 +413,9 @@ ifeq ($(USE_I2C), YES) CDEFS += -DUSE_I2C endif +# Declare all non-optional modules as built-in to force inclusion +CDEFS += ${foreach MOD, ${MODULES}, -DMODULE_$(MOD)_BUILTIN } + # Place project-specific -D and/or -U options for # Assembler with preprocessor here. #ADEFS = -DUSE_IRQ_ASM_WRAPPER @@ -426,11 +442,15 @@ CSTANDARD = -std=gnu99 # Flags for C and C++ (arm-elf-gcc/arm-elf-g++) ifeq ($(DEBUG),YES) -CFLAGS = -DDEBUG +CFLAGS += -DDEBUG endif ifeq ($(DIAGNOSTICS),YES) -CFLAGS = -DDIAGNOSTICS +CFLAGS += -DDIAGNOSTICS +endif + +ifeq ($(DIAG_TASKS),YES) +CFLAGS += -DDIAG_TASKS endif CFLAGS += -g$(DEBUGF) diff --git a/flight/CopterControl/System/inc/FreeRTOSConfig.h b/flight/CopterControl/System/inc/FreeRTOSConfig.h index 994956008..68bb9da0e 100644 --- a/flight/CopterControl/System/inc/FreeRTOSConfig.h +++ b/flight/CopterControl/System/inc/FreeRTOSConfig.h @@ -76,7 +76,7 @@ NVIC value of 255. */ #endif /* Enable run time stats collection */ -#if defined(DIAGNOSTICS) +#if defined(DIAG_TASKS) #define configCHECK_FOR_STACK_OVERFLOW 2 #define configGENERATE_RUN_TIME_STATS 1 diff --git a/flight/CopterControl/System/inc/pios_config.h b/flight/CopterControl/System/inc/pios_config.h index 8e29e0b73..004104f70 100644 --- a/flight/CopterControl/System/inc/pios_config.h +++ b/flight/CopterControl/System/inc/pios_config.h @@ -42,6 +42,7 @@ #endif #define PIOS_INCLUDE_IRQ #define PIOS_INCLUDE_LED +#define PIOS_INCLUDE_IAP #define PIOS_INCLUDE_RCVR @@ -61,7 +62,9 @@ #define PIOS_INCLUDE_SPI #define PIOS_INCLUDE_SYS #define PIOS_INCLUDE_USART +#define PIOS_INCLUDE_USB #define PIOS_INCLUDE_USB_HID +#define PIOS_INCLUDE_USB_CDC #define PIOS_INCLUDE_COM #define PIOS_INCLUDE_SETTINGS #define PIOS_INCLUDE_FREERTOS @@ -74,6 +77,8 @@ #define PIOS_INCLUDE_ADXL345 #define PIOS_INCLUDE_FLASH +#define PIOS_INCLUDE_BMP085 + /* A really shitty setting saving implementation */ #define PIOS_INCLUDE_FLASH_SECTOR_SETTINGS diff --git a/flight/CopterControl/System/inc/pios_usb.h b/flight/CopterControl/System/inc/pios_usb.h deleted file mode 100644 index 6af496a71..000000000 --- a/flight/CopterControl/System/inc/pios_usb.h +++ /dev/null @@ -1,85 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_USB USB Functions - * @brief PIOS USB interface code - * @{ - * - * @file pios_usb.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) - * @brief USB 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_USB_H -#define PIOS_USB_H - -/* Local defines */ -/* Following settings allow to customise the USB device descriptor */ -#ifndef PIOS_USB_VENDOR_ID -#define PIOS_USB_VENDOR_ID 0x20A0 -#endif - -#ifndef PIOS_USB_VENDOR_STR -#define PIOS_USB_VENDOR_STR "openpilot.org" -#endif - -#ifndef PIOS_USB_PRODUCT_STR -#define PIOS_USB_PRODUCT_STR "CopterControl" -#endif - -#ifndef PIOS_USB_PRODUCT_ID -#define PIOS_USB_PRODUCT_ID 0x415B -#endif - -#ifndef PIOS_USB_VERSION_ID -#define PIOS_USB_VERSION_ID 0x0402 /* CopterControl board (04), Running state (02) */ -#endif - -/* Internal defines which are used by PIOS USB HID (don't touch) */ -#define PIOS_USB_EP_NUM 2 - -/* Buffer table base address */ -#define PIOS_USB_BTABLE_ADDRESS 0x000 - -/* EP0 rx/tx buffer base address */ -#define PIOS_USB_ENDP0_RXADDR 0x040 -#define PIOS_USB_ENDP0_TXADDR 0x080 - -/* EP1 Rx/Tx buffer base address for HID driver */ -#define PIOS_USB_ENDP1_TXADDR 0x0C0 -#define PIOS_USB_ENDP1_RXADDR 0x100 - -/* Global Variables */ -extern void (*pEpInt_IN[7]) (void); -extern void (*pEpInt_OUT[7]) (void); - -/* Public Functions */ -extern int32_t PIOS_USB_Init(uint32_t mode); -extern int32_t PIOS_USB_IsInitialized(void); -extern int32_t PIOS_USB_CableConnected(void); - -#endif /* PIOS_USB_H */ - -/** - * @} - * @} - */ diff --git a/flight/CopterControl/System/inc/pios_usb_board_data.h b/flight/CopterControl/System/inc/pios_usb_board_data.h new file mode 100644 index 000000000..9907a4934 --- /dev/null +++ b/flight/CopterControl/System/inc/pios_usb_board_data.h @@ -0,0 +1,45 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB_BOARD Board specific USB definitions + * @brief Board specific USB definitions + * @{ + * + * @file pios_usb_board_data.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Board specific USB definitions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_USB_BOARD_DATA_H +#define PIOS_USB_BOARD_DATA_H + +#define PIOS_USB_BOARD_CDC_DATA_LENGTH 64 +#define PIOS_USB_BOARD_CDC_MGMT_LENGTH 32 +#define PIOS_USB_BOARD_HID_DATA_LENGTH 64 + +#define PIOS_USB_BOARD_EP_NUM 4 + +#include "pios_usb_defs.h" /* USB_* macros */ + +#define PIOS_USB_BOARD_PRODUCT_ID USB_PRODUCT_ID_COPTERCONTROL +#define PIOS_USB_BOARD_DEVICE_VER USB_OP_DEVICE_VER(USB_OP_BOARD_ID_COPTERCONTROL, USB_OP_BOARD_MODE_FW) + +#endif /* PIOS_USB_BOARD_DATA_H */ diff --git a/flight/CopterControl/System/inc/pios_usb_hid_desc.h b/flight/CopterControl/System/inc/pios_usb_hid_desc.h deleted file mode 100644 index ae72ebfb8..000000000 --- a/flight/CopterControl/System/inc/pios_usb_hid_desc.h +++ /dev/null @@ -1,56 +0,0 @@ -/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** -* File Name : usb_desc.h -* Author : MCD Application Team -* Version : V3.2.1 -* Date : 07/05/2010 -* Description : Descriptor Header for Custom HID Demo -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __USB_DESC_H -#define __USB_DESC_H - -/* Includes ------------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ -/* Exported define -----------------------------------------------------------*/ -#define USB_DEVICE_DESCRIPTOR_TYPE 0x01 -#define USB_CONFIGURATION_DESCRIPTOR_TYPE 0x02 -#define USB_STRING_DESCRIPTOR_TYPE 0x03 -#define USB_INTERFACE_DESCRIPTOR_TYPE 0x04 -#define USB_ENDPOINT_DESCRIPTOR_TYPE 0x05 - -#define HID_DESCRIPTOR_TYPE 0x21 -#define PIOS_HID_SIZ_HID_DESC 0x09 -#define PIOS_HID_OFF_HID_DESC 0x12 - -#define PIOS_HID_SIZ_DEVICE_DESC 18 -#define PIOS_HID_SIZ_CONFIG_DESC 41 -#define PIOS_HID_SIZ_REPORT_DESC 36 -#define PIOS_HID_SIZ_STRING_LANGID 4 -#define PIOS_HID_SIZ_STRING_VENDOR 28 -#define PIOS_HID_SIZ_STRING_PRODUCT 28 -#define PIOS_HID_SIZ_STRING_SERIAL 52 /* 96 bits, 12 bytes, 24 characters, 48 in unicode */ - -#define STANDARD_ENDPOINT_DESC_SIZE 0x09 - -/* Exported functions ------------------------------------------------------- */ -extern const uint8_t PIOS_HID_DeviceDescriptor[PIOS_HID_SIZ_DEVICE_DESC]; -extern const uint8_t PIOS_HID_ConfigDescriptor[PIOS_HID_SIZ_CONFIG_DESC]; -extern const uint8_t PIOS_HID_ReportDescriptor[PIOS_HID_SIZ_REPORT_DESC]; -extern const uint8_t PIOS_HID_StringLangID[PIOS_HID_SIZ_STRING_LANGID]; -extern const uint8_t PIOS_HID_StringVendor[PIOS_HID_SIZ_STRING_VENDOR]; -extern const uint8_t PIOS_HID_StringProduct[PIOS_HID_SIZ_STRING_PRODUCT]; -extern uint8_t PIOS_HID_StringSerial[PIOS_HID_SIZ_STRING_SERIAL]; - -#endif /* __USB_DESC_H */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/CopterControl/System/pios_board.c b/flight/CopterControl/System/pios_board.c index d89342787..a7197768d 100644 --- a/flight/CopterControl/System/pios_board.c +++ b/flight/CopterControl/System/pios_board.c @@ -541,11 +541,7 @@ static const struct pios_tim_channel pios_tim_servoport_rcvrport_pins[] = { #include "pios_usart_priv.h" -#if defined(PIOS_INCLUDE_TELEMETRY_RF) -/* - * Telemetry USART - */ -static const struct pios_usart_cfg pios_usart_telem_main_cfg = { +static const struct pios_usart_cfg pios_usart_generic_main_cfg = { .regs = USART1, .init = { .USART_BaudRate = 57600, @@ -581,7 +577,7 @@ static const struct pios_usart_cfg pios_usart_telem_main_cfg = { }, }; -static const struct pios_usart_cfg pios_usart_telem_flexi_cfg = { +static const struct pios_usart_cfg pios_usart_generic_flexi_cfg = { .regs = USART3, .init = { .USART_BaudRate = 57600, @@ -616,84 +612,6 @@ static const struct pios_usart_cfg pios_usart_telem_flexi_cfg = { }, }, }; -#endif /* PIOS_INCLUDE_TELEMETRY_RF */ - -#if defined(PIOS_INCLUDE_GPS) -/* - * GPS USART - */ -static const struct pios_usart_cfg pios_usart_gps_main_cfg = { - .regs = USART1, - .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 = USART1_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .rx = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_10, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_IPU, - }, - }, - .tx = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_9, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF_PP, - }, - }, -}; - -static const struct pios_usart_cfg pios_usart_gps_flexi_cfg = { - .regs = USART3, - .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 = USART3_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .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_AF_PP, - }, - }, -}; -#endif /* PIOS_INCLUDE_GPS */ #if defined(PIOS_INCLUDE_DSM) /* @@ -862,13 +780,16 @@ static const struct pios_sbus_cfg pios_sbus_cfg = { #include "pios_com_priv.h" -#define PIOS_COM_TELEM_RF_RX_BUF_LEN 192 -#define PIOS_COM_TELEM_RF_TX_BUF_LEN 192 +#define PIOS_COM_TELEM_RF_RX_BUF_LEN 32 +#define PIOS_COM_TELEM_RF_TX_BUF_LEN 12 #define PIOS_COM_GPS_RX_BUF_LEN 32 -#define PIOS_COM_TELEM_USB_RX_BUF_LEN 192 -#define PIOS_COM_TELEM_USB_TX_BUF_LEN 192 +#define PIOS_COM_TELEM_USB_RX_BUF_LEN 65 +#define PIOS_COM_TELEM_USB_TX_BUF_LEN 65 + +#define PIOS_COM_BRIDGE_RX_BUF_LEN 65 +#define PIOS_COM_BRIDGE_TX_BUF_LEN 12 #endif /* PIOS_INCLUDE_COM */ @@ -982,12 +903,12 @@ const struct pios_pwm_cfg pios_pwm_cfg = { * I2C Adapters */ -void PIOS_I2C_main_adapter_ev_irq_handler(void); -void PIOS_I2C_main_adapter_er_irq_handler(void); -void I2C2_EV_IRQHandler() __attribute__ ((alias ("PIOS_I2C_main_adapter_ev_irq_handler"))); -void I2C2_ER_IRQHandler() __attribute__ ((alias ("PIOS_I2C_main_adapter_er_irq_handler"))); +void PIOS_I2C_flexi_adapter_ev_irq_handler(void); +void PIOS_I2C_flexi_adapter_er_irq_handler(void); +void I2C2_EV_IRQHandler() __attribute__ ((alias ("PIOS_I2C_flexi_adapter_ev_irq_handler"))); +void I2C2_ER_IRQHandler() __attribute__ ((alias ("PIOS_I2C_flexi_adapter_er_irq_handler"))); -static const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = { +static const struct pios_i2c_adapter_cfg pios_i2c_flexi_adapter_cfg = { .regs = I2C2, .init = { .I2C_Mode = I2C_Mode_I2C, @@ -1034,17 +955,17 @@ static const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = { }, }; -uint32_t pios_i2c_main_adapter_id; -void PIOS_I2C_main_adapter_ev_irq_handler(void) +uint32_t pios_i2c_flexi_adapter_id; +void PIOS_I2C_flexi_adapter_ev_irq_handler(void) { /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_I2C_EV_IRQ_Handler(pios_i2c_main_adapter_id); + PIOS_I2C_EV_IRQ_Handler(pios_i2c_flexi_adapter_id); } -void PIOS_I2C_main_adapter_er_irq_handler(void) +void PIOS_I2C_flexi_adapter_er_irq_handler(void) { /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_I2C_ER_IRQ_Handler(pios_i2c_main_adapter_id); + PIOS_I2C_ER_IRQ_Handler(pios_i2c_flexi_adapter_id); } #endif /* PIOS_INCLUDE_I2C */ @@ -1064,10 +985,10 @@ uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE]; #endif /* PIOS_INCLUDE_RCVR */ -#if defined(PIOS_INCLUDE_USB_HID) -#include "pios_usb_hid_priv.h" +#if defined(PIOS_INCLUDE_USB) +#include "pios_usb_priv.h" -static const struct pios_usb_hid_cfg pios_usb_hid_main_cfg = { +static const struct pios_usb_cfg pios_usb_main_cfg = { .irq = { .init = { .NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn, @@ -1077,13 +998,41 @@ static const struct pios_usb_hid_cfg pios_usb_hid_main_cfg = { }, }, }; -#endif /* PIOS_INCLUDE_USB_HID */ -extern const struct pios_com_driver pios_usb_com_driver; +#include "pios_usb_board_data_priv.h" +#include "pios_usb_desc_hid_cdc_priv.h" +#include "pios_usb_desc_hid_only_priv.h" + +#endif /* PIOS_INCLUDE_USB */ + +#if defined(PIOS_INCLUDE_USB_HID) +#include + +const struct pios_usb_hid_cfg pios_usb_hid_cfg = { + .data_if = 0, + .data_rx_ep = 1, + .data_tx_ep = 1, +}; +#endif /* PIOS_INCLUDE_USB_HID */ + +#if defined(PIOS_INCLUDE_USB_CDC) +#include + +const struct pios_usb_cdc_cfg pios_usb_cdc_cfg = { + .ctrl_if = 1, + .ctrl_tx_ep = 2, + + .data_if = 2, + .data_rx_ep = 3, + .data_tx_ep = 3, +}; +#endif /* PIOS_INCLUDE_USB_CDC */ uint32_t pios_com_telem_rf_id; uint32_t pios_com_telem_usb_id; +uint32_t pios_com_vcp_id; uint32_t pios_com_gps_id; +uint32_t pios_com_bridge_id; /** * PIOS_Board_Init() @@ -1110,15 +1059,32 @@ void PIOS_Board_Init(void) { UAVObjInitialize(); HwSettingsInitialize(); - -#if defined(PIOS_INCLUDE_RTC) - /* Initialize the real-time clock and its associated tick */ - PIOS_RTC_Init(&pios_rtc_main_cfg); + +#ifndef ERASE_FLASH + /* Initialize watchdog as early as possible to catch faults during init */ + PIOS_WDG_Init(); #endif /* Initialize the alarms library */ AlarmsInitialize(); + /* Check for repeated boot failures */ + PIOS_IAP_Init(); + uint16_t boot_count = PIOS_IAP_ReadBootCount(); + if (boot_count < 3) { + PIOS_IAP_WriteBootCount(++boot_count); + AlarmsClear(SYSTEMALARMS_ALARM_BOOTFAULT); + } else { + /* Too many failed boot attempts, force hwsettings to defaults */ + HwSettingsSetDefaults(HwSettingsHandle(), 0); + AlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT, SYSTEMALARMS_ALARM_CRITICAL); + } + +#if defined(PIOS_INCLUDE_RTC) + /* Initialize the real-time clock and its associated tick */ + PIOS_RTC_Init(&pios_rtc_main_cfg); +#endif + /* Initialize the task monitor library */ TaskMonitorInitialize(); @@ -1128,6 +1094,133 @@ void PIOS_Board_Init(void) { PIOS_TIM_InitClock(&tim_3_cfg); PIOS_TIM_InitClock(&tim_4_cfg); +#if defined(PIOS_INCLUDE_USB) + /* Initialize board specific USB data */ + PIOS_USB_BOARD_DATA_Init(); + + /* Flags to determine if various USB interfaces are advertised */ + bool usb_hid_present = false; + bool usb_cdc_present = false; + + uint8_t hwsettings_usb_devicetype; + HwSettingsUSB_DeviceTypeGet(&hwsettings_usb_devicetype); + + switch (hwsettings_usb_devicetype) { + case HWSETTINGS_USB_DEVICETYPE_HIDONLY: + if (PIOS_USB_DESC_HID_ONLY_Init()) { + PIOS_Assert(0); + } + usb_hid_present = true; + break; + case HWSETTINGS_USB_DEVICETYPE_HIDVCP: + if (PIOS_USB_DESC_HID_CDC_Init()) { + PIOS_Assert(0); + } + usb_hid_present = true; + usb_cdc_present = true; + break; + case HWSETTINGS_USB_DEVICETYPE_VCPONLY: + break; + default: + PIOS_Assert(0); + } + + uint32_t pios_usb_id; + PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg); + +#if defined(PIOS_INCLUDE_USB_CDC) + + uint8_t hwsettings_usb_vcpport; + /* Configure the USB VCP port */ + HwSettingsUSB_VCPPortGet(&hwsettings_usb_vcpport); + + if (!usb_cdc_present) { + /* Force VCP port function to disabled if we haven't advertised VCP in our USB descriptor */ + hwsettings_usb_vcpport = HWSETTINGS_USB_VCPPORT_DISABLED; + } + + switch (hwsettings_usb_vcpport) { + case HWSETTINGS_USB_VCPPORT_DISABLED: + 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)) { + PIOS_Assert(0); + } + uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_RX_BUF_LEN); + uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_TX_BUF_LEN); + PIOS_Assert(rx_buffer); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, + rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN, + tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) { + PIOS_Assert(0); + } + } +#endif /* PIOS_INCLUDE_COM */ + break; + case HWSETTINGS_USB_VCPPORT_COMBRIDGE: +#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)) { + PIOS_Assert(0); + } + uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_BRIDGE_RX_BUF_LEN); + uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_BRIDGE_TX_BUF_LEN); + PIOS_Assert(rx_buffer); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_vcp_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, + rx_buffer, PIOS_COM_BRIDGE_RX_BUF_LEN, + tx_buffer, PIOS_COM_BRIDGE_TX_BUF_LEN)) { + PIOS_Assert(0); + } + } +#endif /* PIOS_INCLUDE_COM */ + break; + } +#endif /* PIOS_INCLUDE_USB_CDC */ + +#if defined(PIOS_INCLUDE_USB_HID) + /* Configure the usb HID port */ + uint8_t hwsettings_usb_hidport; + HwSettingsUSB_HIDPortGet(&hwsettings_usb_hidport); + + if (!usb_hid_present) { + /* Force HID port function to disabled if we haven't advertised HID in our USB descriptor */ + hwsettings_usb_hidport = HWSETTINGS_USB_HIDPORT_DISABLED; + } + + switch (hwsettings_usb_hidport) { + case HWSETTINGS_USB_HIDPORT_DISABLED: + break; + case HWSETTINGS_USB_HIDPORT_USBTELEMETRY: +#if defined(PIOS_INCLUDE_COM) + { + uint32_t pios_usb_hid_id; + if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) { + PIOS_Assert(0); + } + uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_RX_BUF_LEN); + uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_TX_BUF_LEN); + PIOS_Assert(rx_buffer); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id, + rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN, + tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) { + PIOS_Assert(0); + } + } +#endif /* PIOS_INCLUDE_COM */ + break; + } + +#endif /* PIOS_INCLUDE_USB_HID */ + +#endif /* PIOS_INCLUDE_USB */ + /* Configure the main IO port */ uint8_t hwsettings_DSMxBind; HwSettingsDSMxBindGet(&hwsettings_DSMxBind); @@ -1140,8 +1233,8 @@ void PIOS_Board_Init(void) { case HWSETTINGS_CC_MAINPORT_TELEMETRY: #if defined(PIOS_INCLUDE_TELEMETRY_RF) { - uint32_t pios_usart_telem_rf_id; - if (PIOS_USART_Init(&pios_usart_telem_rf_id, &pios_usart_telem_main_cfg)) { + uint32_t pios_usart_generic_id; + if (PIOS_USART_Init(&pios_usart_generic_id, &pios_usart_generic_main_cfg)) { PIOS_Assert(0); } @@ -1149,7 +1242,7 @@ void PIOS_Board_Init(void) { uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_TX_BUF_LEN); PIOS_Assert(rx_buffer); PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_usart_com_driver, pios_usart_telem_rf_id, + if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_usart_com_driver, pios_usart_generic_id, rx_buffer, PIOS_COM_TELEM_RF_RX_BUF_LEN, tx_buffer, PIOS_COM_TELEM_RF_TX_BUF_LEN)) { PIOS_Assert(0); @@ -1182,14 +1275,14 @@ void PIOS_Board_Init(void) { case HWSETTINGS_CC_MAINPORT_GPS: #if defined(PIOS_INCLUDE_GPS) { - uint32_t pios_usart_gps_id; - if (PIOS_USART_Init(&pios_usart_gps_id, &pios_usart_gps_main_cfg)) { + uint32_t pios_usart_generic_id; + if (PIOS_USART_Init(&pios_usart_generic_id, &pios_usart_generic_main_cfg)) { PIOS_Assert(0); } uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_GPS_RX_BUF_LEN); PIOS_Assert(rx_buffer); - if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_gps_id, + if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_generic_id, rx_buffer, PIOS_COM_GPS_RX_BUF_LEN, NULL, 0)) { PIOS_Assert(0); @@ -1242,6 +1335,24 @@ void PIOS_Board_Init(void) { break; case HWSETTINGS_CC_MAINPORT_COMAUX: break; + case HWSETTINGS_CC_MAINPORT_COMBRIDGE: + { + uint32_t pios_usart_generic_id; + if (PIOS_USART_Init(&pios_usart_generic_id, &pios_usart_generic_main_cfg)) { + PIOS_Assert(0); + } + + uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_BRIDGE_RX_BUF_LEN); + PIOS_Assert(rx_buffer); + uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_BRIDGE_TX_BUF_LEN); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_bridge_id, &pios_usart_com_driver, pios_usart_generic_id, + rx_buffer, PIOS_COM_BRIDGE_RX_BUF_LEN, + tx_buffer, PIOS_COM_BRIDGE_TX_BUF_LEN)) { + PIOS_Assert(0); + } + } + break; } /* Configure the flexi port */ @@ -1254,15 +1365,15 @@ void PIOS_Board_Init(void) { case HWSETTINGS_CC_FLEXIPORT_TELEMETRY: #if defined(PIOS_INCLUDE_TELEMETRY_RF) { - uint32_t pios_usart_telem_rf_id; - if (PIOS_USART_Init(&pios_usart_telem_rf_id, &pios_usart_telem_flexi_cfg)) { + uint32_t pios_usart_generic_id; + if (PIOS_USART_Init(&pios_usart_generic_id, &pios_usart_generic_flexi_cfg)) { PIOS_Assert(0); } uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_RX_BUF_LEN); uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_TX_BUF_LEN); PIOS_Assert(rx_buffer); PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_usart_com_driver, pios_usart_telem_rf_id, + if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_usart_com_driver, pios_usart_generic_id, rx_buffer, PIOS_COM_TELEM_RF_RX_BUF_LEN, tx_buffer, PIOS_COM_TELEM_RF_TX_BUF_LEN)) { PIOS_Assert(0); @@ -1270,16 +1381,34 @@ void PIOS_Board_Init(void) { } #endif /* PIOS_INCLUDE_TELEMETRY_RF */ break; + case HWSETTINGS_CC_FLEXIPORT_COMBRIDGE: + { + uint32_t pios_usart_generic_id; + if (PIOS_USART_Init(&pios_usart_generic_id, &pios_usart_generic_flexi_cfg)) { + PIOS_Assert(0); + } + + uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_BRIDGE_RX_BUF_LEN); + uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_BRIDGE_TX_BUF_LEN); + PIOS_Assert(rx_buffer); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_bridge_id, &pios_usart_com_driver, pios_usart_generic_id, + rx_buffer, PIOS_COM_BRIDGE_RX_BUF_LEN, + tx_buffer, PIOS_COM_BRIDGE_TX_BUF_LEN)) { + PIOS_Assert(0); + } + } + break; case HWSETTINGS_CC_FLEXIPORT_GPS: #if defined(PIOS_INCLUDE_GPS) { - uint32_t pios_usart_gps_id; - if (PIOS_USART_Init(&pios_usart_gps_id, &pios_usart_gps_flexi_cfg)) { + uint32_t pios_usart_generic_id; + if (PIOS_USART_Init(&pios_usart_generic_id, &pios_usart_generic_flexi_cfg)) { PIOS_Assert(0); } uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_GPS_RX_BUF_LEN); PIOS_Assert(rx_buffer); - if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_gps_id, + if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_generic_id, rx_buffer, PIOS_COM_GPS_RX_BUF_LEN, NULL, 0)) { PIOS_Assert(0); @@ -1335,7 +1464,7 @@ void PIOS_Board_Init(void) { case HWSETTINGS_CC_FLEXIPORT_I2C: #if defined(PIOS_INCLUDE_I2C) { - if (PIOS_I2C_Init(&pios_i2c_main_adapter_id, &pios_i2c_main_adapter_cfg)) { + if (PIOS_I2C_Init(&pios_i2c_flexi_adapter_id, &pios_i2c_flexi_adapter_cfg)) { PIOS_Assert(0); } } @@ -1391,7 +1520,7 @@ void PIOS_Board_Init(void) { pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_GCS] = pios_gcsrcvr_rcvr_id; #endif /* PIOS_INCLUDE_GCSRCVR */ - /* Remap AFIO pin */ + /* Remap AFIO pin for PB4 (Servo 5 Out)*/ GPIO_PinRemapConfig( GPIO_Remap_SWJ_NoJTRST, ENABLE); #ifndef PIOS_DEBUG_ENABLE_DEBUG_PINS @@ -1413,26 +1542,8 @@ void PIOS_Board_Init(void) { PIOS_ADC_Init(); PIOS_GPIO_Init(); -#if defined(PIOS_INCLUDE_USB_HID) - uint32_t pios_usb_hid_id; - PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_main_cfg); -#if defined(PIOS_INCLUDE_COM) - uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_USB_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_com_driver, pios_usb_hid_id, - rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN, - tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) { - PIOS_Assert(0); - } -#endif /* PIOS_INCLUDE_COM */ -#endif /* PIOS_INCLUDE_USB_HID */ - - PIOS_IAP_Init(); -#ifndef ERASE_FLASH - PIOS_WDG_Init(); -#endif + /* Make sure we have at least one telemetry link configured or else fail initialization */ + PIOS_Assert(pios_com_telem_rf_id || pios_com_telem_usb_id); } /** diff --git a/flight/CopterControl/System/pios_usb_board_data.c b/flight/CopterControl/System/pios_usb_board_data.c new file mode 100644 index 000000000..4f02ce424 --- /dev/null +++ b/flight/CopterControl/System/pios_usb_board_data.c @@ -0,0 +1,123 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB_BOARD Board specific USB definitions + * @brief Board specific USB definitions + * @{ + * + * @file pios_usb_board_data.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Board specific USB definitions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "pios_usb_board_data.h" /* struct usb_*, USB_* */ +#include "pios_sys.h" /* PIOS_SYS_SerialNumberGet */ +#include "pios_usbhook.h" /* PIOS_USBHOOK_* */ + +static const uint8_t usb_product_id[28] = { + sizeof(usb_product_id), + USB_DESC_TYPE_STRING, + 'C', 0, + 'o', 0, + 'p', 0, + 't', 0, + 'e', 0, + 'r', 0, + 'C', 0, + 'o', 0, + 'n', 0, + 't', 0, + 'r', 0, + 'o', 0, + 'l', 0, +}; + +static uint8_t usb_serial_number[52] = { + sizeof(usb_serial_number), + USB_DESC_TYPE_STRING, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0 +}; + +static const struct usb_string_langid usb_lang_id = { + .bLength = sizeof(usb_lang_id), + .bDescriptorType = USB_DESC_TYPE_STRING, + .bLangID = htousbs(USB_LANGID_ENGLISH_UK), +}; + +static const uint8_t usb_vendor_id[28] = { + sizeof(usb_vendor_id), + USB_DESC_TYPE_STRING, + 'o', 0, + 'p', 0, + 'e', 0, + 'n', 0, + 'p', 0, + 'i', 0, + 'l', 0, + 'o', 0, + 't', 0, + '.', 0, + 'o', 0, + 'r', 0, + 'g', 0 +}; + +int32_t PIOS_USB_BOARD_DATA_Init(void) +{ + /* Load device serial number into serial number string */ + uint8_t sn[25]; + PIOS_SYS_SerialNumberGet((char *)sn); + for (uint8_t i = 0; sn[i] != '\0' && (2 * i) < usb_serial_number[0]; i++) { + usb_serial_number[2 + 2 * i] = sn[i]; + } + + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_PRODUCT, (uint8_t *)&usb_product_id, sizeof(usb_product_id)); + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_SERIAL, (uint8_t *)&usb_serial_number, sizeof(usb_serial_number)); + + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_LANG, (uint8_t *)&usb_lang_id, sizeof(usb_lang_id)); + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_VENDOR, (uint8_t *)&usb_vendor_id, sizeof(usb_vendor_id)); + + return 0; +} diff --git a/flight/CopterControl/System/pios_usb_hid_desc.c b/flight/CopterControl/System/pios_usb_hid_desc.c deleted file mode 100644 index 6296b0593..000000000 --- a/flight/CopterControl/System/pios_usb_hid_desc.c +++ /dev/null @@ -1,224 +0,0 @@ -/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** -* File Name : usb_desc.c -* Author : MCD Application Team -* Version : V3.2.1 -* Date : 07/05/2010 -* Description : Descriptors for Custom HID Demo -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ - -#include "usb_lib.h" -#include "pios_usb.h" -#include "pios_usb_hid.h" -#include "pios_usb_hid_desc.h" - -// ************************************************* -// USB Standard Device Descriptor - -const uint8_t PIOS_HID_DeviceDescriptor[PIOS_HID_SIZ_DEVICE_DESC] = - { - 0x12, // bLength - USB_DEVICE_DESCRIPTOR_TYPE, // bDescriptorType - 0x00, // bcdUSB - 0x02, - 0x00, // bDeviceClass - 0x00, // bDeviceSubClass - 0x00, // bDeviceProtocol - 0x40, // bMaxPacketSize40 - (uint8_t)((PIOS_USB_VENDOR_ID) & 0xff), // idVendor - (uint8_t)((PIOS_USB_VENDOR_ID) >> 8), - (uint8_t)((PIOS_USB_PRODUCT_ID) & 0xff), // idProduct - (uint8_t)((PIOS_USB_PRODUCT_ID) >> 8), - (uint8_t)((PIOS_USB_VERSION_ID) & 0xff), // bcdDevice - (uint8_t)((PIOS_USB_VERSION_ID) >> 8), - 0x01, // Index of string descriptor describing manufacturer - 0x02, // Index of string descriptor describing product - 0x03, // Index of string descriptor describing the device serial number - 0x01 // bNumConfigurations - }; - -// ************************************************* -// USB Configuration Descriptor -// All Descriptors (Configuration, Interface, Endpoint, Class, Vendor - -const uint8_t PIOS_HID_ConfigDescriptor[PIOS_HID_SIZ_CONFIG_DESC] = - { - 0x09, // bLength: Configuation Descriptor size - USB_CONFIGURATION_DESCRIPTOR_TYPE, // bDescriptorType: Configuration - PIOS_HID_SIZ_CONFIG_DESC, - // wTotalLength: Bytes returned - 0x00, - 0x01, // bNumInterfaces: 1 interface - 0x01, // bConfigurationValue: Configuration value - 0x00, // iConfiguration: Index of string descriptor describing the configuration - 0xC0, // bmAttributes: Bus powered - 0x7D, // MaxPower 250 mA - needed to power the RF transmitter - - // ************** Descriptor of Custom HID interface **************** - // 09 - 0x09, // bLength: Interface Descriptor size - USB_INTERFACE_DESCRIPTOR_TYPE, // bDescriptorType: Interface descriptor type - 0x00, // bInterfaceNumber: Number of Interface - 0x00, // bAlternateSetting: Alternate setting - 0x02, // bNumEndpoints - 0x03, // bInterfaceClass: HID - 0x00, // bInterfaceSubClass : 1=BOOT, 0=no boot - 0x00, // nInterfaceProtocol : 0=none, 1=keyboard, 2=mouse - 0, // iInterface: Index of string descriptor - - // ******************** Descriptor of Custom HID HID ******************** - // 18 - 0x09, // bLength: HID Descriptor size - HID_DESCRIPTOR_TYPE, // bDescriptorType: HID - 0x10, // bcdHID: HID Class Spec release number - 0x01, - 0x00, // bCountryCode: Hardware target country - 0x01, // bNumDescriptors: Number of HID class descriptors to follow - 0x22, // bDescriptorType - PIOS_HID_SIZ_REPORT_DESC, // wItemLength: Total length of Report descriptor - 0x00, - - // ******************** Descriptor of Custom HID endpoints ****************** - // 27 - 0x07, // bLength: Endpoint Descriptor size - USB_ENDPOINT_DESCRIPTOR_TYPE, // bDescriptorType: - - 0x81, // bEndpointAddress: Endpoint Address (IN) - 0x03, // bmAttributes: Interrupt endpoint - 0x40, // wMaxPacketSize: 2 Bytes max - 0x00, - 0x04, // bInterval: Polling Interval in ms - // 34 - - 0x07, // bLength: Endpoint Descriptor size - USB_ENDPOINT_DESCRIPTOR_TYPE, // bDescriptorType: - // Endpoint descriptor type - 0x01, // bEndpointAddress: - // Endpoint Address (OUT) - 0x03, // bmAttributes: Interrupt endpoint - 0x40, // wMaxPacketSize: 2 Bytes max - 0x00, - 0x04, // bInterval: Polling Interval in ms - // 41 - }; - -// ************************************************* - - const uint8_t PIOS_HID_ReportDescriptor[PIOS_HID_SIZ_REPORT_DESC] = - { - 0x06, 0x9c, 0xff, // USAGE_PAGE (Vendor Page: 0xFF00) - 0x09, 0x01, // USAGE (Demo Kit) - 0xa1, 0x01, // COLLECTION (Application) - // 6 - - // Data 1 - 0x85, 0x01, // REPORT_ID (1) - 0x09, 0x02, // USAGE (LED 1) - 0x15, 0x00, // LOGICAL_MINIMUM (0) - 0x25, 0xff, // LOGICAL_MAXIMUM (255) - 0x75, 0x08, // REPORT_SIZE (8) - 0x95, PIOS_USB_HID_DATA_LENGTH+1, // REPORT_COUNT (1) - 0x81, 0x83, // INPUT (Const,Var,Array) - // 20 - - // Data 1 - 0x85, 0x02, // REPORT_ID (2) - 0x09, 0x03, // USAGE (LED 1) - 0x15, 0x00, // LOGICAL_MINIMUM (0) - 0x25, 0xff, // LOGICAL_MAXIMUM (255) - 0x75, 0x08, // REPORT_SIZE (8) - 0x95, PIOS_USB_HID_DATA_LENGTH+1, // REPORT_COUNT (1) - 0x91, 0x82, // OUTPUT (Data,Var,Abs,Vol) - // 34 - - 0xc0 // END_COLLECTION - }; - -// ************************************************* -// USB String Descriptors (optional) - -const uint8_t PIOS_HID_StringLangID[PIOS_HID_SIZ_STRING_LANGID] = - { - PIOS_HID_SIZ_STRING_LANGID, - USB_STRING_DESCRIPTOR_TYPE, - 0x09, 0x08 // LangID = 0x0809: UK. English -// 0x09, 0x04 // LangID = 0x0409: U.S. English - }; - -const uint8_t PIOS_HID_StringVendor[PIOS_HID_SIZ_STRING_VENDOR] = - { - PIOS_HID_SIZ_STRING_VENDOR, // Size of Vendor string - USB_STRING_DESCRIPTOR_TYPE, // bDescriptorType - // Manufacturer: "STMicroelectronics" - 'o', 0, - 'p', 0, - 'e', 0, - 'n', 0, - 'p', 0, - 'i', 0, - 'l', 0, - 'o', 0, - 't', 0, - '.', 0, - 'o', 0, - 'r', 0, - 'g', 0 - }; - -const uint8_t PIOS_HID_StringProduct[PIOS_HID_SIZ_STRING_PRODUCT] = - { - PIOS_HID_SIZ_STRING_PRODUCT, // bLength - USB_STRING_DESCRIPTOR_TYPE, // bDescriptorType - 'C', 0, - 'o', 0, - 'p', 0, - 't', 0, - 'e', 0, - 'r', 0, - 'C', 0, - 'o', 0, - 'n', 0, - 't', 0, - 'r', 0, - 'o', 0, - 'l', 0 - }; - -uint8_t PIOS_HID_StringSerial[PIOS_HID_SIZ_STRING_SERIAL] = - { - PIOS_HID_SIZ_STRING_SERIAL, // bLength - USB_STRING_DESCRIPTOR_TYPE, // bDescriptorType - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0 - }; - -// ************************************************* diff --git a/flight/CopterControl/System/taskmonitor.c b/flight/CopterControl/System/taskmonitor.c deleted file mode 100644 index 6ff6299d0..000000000 --- a/flight/CopterControl/System/taskmonitor.c +++ /dev/null @@ -1,131 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotLibraries OpenPilot System Libraries - * @{ - * @file taskmonitor.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Task monitoring library - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#include "openpilot.h" -//#include "taskmonitor.h" - -// Private constants - -// Private types - -// Private variables -static xSemaphoreHandle lock; -static xTaskHandle handles[TASKINFO_RUNNING_NUMELEM]; -static uint32_t lastMonitorTime; - -// Private functions - -/** - * Initialize library - */ -int32_t TaskMonitorInitialize(void) -{ - lock = xSemaphoreCreateRecursiveMutex(); - memset(handles, 0, sizeof(xTaskHandle)*TASKINFO_RUNNING_NUMELEM); - lastMonitorTime = 0; -#if defined(DIAGNOSTICS) - lastMonitorTime = portGET_RUN_TIME_COUNTER_VALUE(); -#endif - return 0; -} - -/** - * Register a task handle with the library - */ -int32_t TaskMonitorAdd(TaskInfoRunningElem task, xTaskHandle handle) -{ - if (task < TASKINFO_RUNNING_NUMELEM) - { - xSemaphoreTakeRecursive(lock, portMAX_DELAY); - handles[task] = handle; - xSemaphoreGiveRecursive(lock); - return 0; - } - else - { - return -1; - } -} - -/** - * Update the status of all tasks - */ -void TaskMonitorUpdateAll(void) -{ -#if defined(DIAGNOSTICS) - TaskInfoData data; - int n; - - // Lock - xSemaphoreTakeRecursive(lock, portMAX_DELAY); - -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - uint32_t currentTime; - uint32_t deltaTime; - - /* - * Calculate the amount of elapsed run time between the last time we - * measured and now. Scale so that we can convert task run times - * directly to percentages. - */ - currentTime = portGET_RUN_TIME_COUNTER_VALUE(); - deltaTime = ((currentTime - lastMonitorTime) / 100) ? : 1; /* avoid divide-by-zero if the interval is too small */ - lastMonitorTime = currentTime; -#endif - - // Update all task information - for (n = 0; n < TASKINFO_RUNNING_NUMELEM; ++n) - { - if (handles[n] != 0) - { - data.Running[n] = TASKINFO_RUNNING_TRUE; -#if defined(ARCH_POSIX) || defined(ARCH_WIN32) - data.StackRemaining[n] = 10000; -#else - data.StackRemaining[n] = uxTaskGetStackHighWaterMark(handles[n]) * 4; -#if ( configGENERATE_RUN_TIME_STATS == 1 ) - /* Generate run time stats */ - data.RunningTime[n] = uxTaskGetRunTime(handles[n]) / deltaTime; -#endif -#endif - - } - else - { - data.Running[n] = TASKINFO_RUNNING_FALSE; - data.StackRemaining[n] = 0; - data.RunningTime[n] = 0; - } - } - - // Update object - TaskInfoSet(&data); - - // Done - xSemaphoreGiveRecursive(lock); -#endif -} diff --git a/flight/Revolution/System/inc/taskmonitor.h b/flight/Libraries/inc/taskmonitor.h similarity index 100% rename from flight/Revolution/System/inc/taskmonitor.h rename to flight/Libraries/inc/taskmonitor.h diff --git a/flight/Revolution/System/taskmonitor.c b/flight/Libraries/taskmonitor.c similarity index 94% rename from flight/Revolution/System/taskmonitor.c rename to flight/Libraries/taskmonitor.c index dcd08945c..fffc6435c 100644 --- a/flight/Revolution/System/taskmonitor.c +++ b/flight/Libraries/taskmonitor.c @@ -47,7 +47,7 @@ int32_t TaskMonitorInitialize(void) lock = xSemaphoreCreateRecursiveMutex(); memset(handles, 0, sizeof(xTaskHandle)*TASKINFO_RUNNING_NUMELEM); lastMonitorTime = 0; -#if defined(DIAGNOSTICS) +#if defined(DIAG_TASKS) lastMonitorTime = portGET_RUN_TIME_COUNTER_VALUE(); #endif return 0; @@ -94,7 +94,7 @@ int32_t TaskMonitorRemove(TaskInfoRunningElem task) */ void TaskMonitorUpdateAll(void) { -#if defined(DIAGNOSTICS) +#if defined(DIAG_TASKS) TaskInfoData data; int n; @@ -128,7 +128,6 @@ void TaskMonitorUpdateAll(void) #if ( configGENERATE_RUN_TIME_STATS == 1 ) /* Generate run time stats */ data.RunningTime[n] = uxTaskGetRunTime(handles[n]) / deltaTime; - #endif #endif diff --git a/flight/Modules/Altitude/altitude.c b/flight/Modules/Altitude/altitude.c index 83ffcf531..a39f4b445 100644 --- a/flight/Modules/Altitude/altitude.c +++ b/flight/Modules/Altitude/altitude.c @@ -37,6 +37,7 @@ */ #include "openpilot.h" +#include "hwsettings.h" #include "altitude.h" #include "baroaltitude.h" // object that will be updated by the module #if defined(PIOS_INCLUDE_HCSR04) @@ -46,8 +47,7 @@ // Private constants #define STACK_SIZE_BYTES 500 #define TASK_PRIORITY (tskIDLE_PRIORITY+1) -//#define UPDATE_PERIOD 100 -#define UPDATE_PERIOD 25 +#define UPDATE_PERIOD 50 // Private types @@ -60,7 +60,9 @@ static int32_t alt_ds_temp = 0; static int32_t alt_ds_pres = 0; static int alt_ds_count = 0; -// Private functions +static bool altitudeEnabled; + + // Private functions static void altitudeTask(void *parameters); /** @@ -69,17 +71,19 @@ static void altitudeTask(void *parameters); */ int32_t AltitudeStart() { - - BaroAltitudeInitialize(); -#if defined(PIOS_INCLUDE_HCSR04) - SonarAltitudeInitialze(); -#endif - - // Start main task - xTaskCreate(altitudeTask, (signed char *)"Altitude", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle); - TaskMonitorAdd(TASKINFO_RUNNING_ALTITUDE, taskHandle); - return 0; + if (altitudeEnabled) { + BaroAltitudeInitialize(); +#if defined(PIOS_INCLUDE_HCSR04) + SonarAltitudeInitialze(); +#endif + + // Start main task + xTaskCreate(altitudeTask, (signed char *)"Altitude", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle); + TaskMonitorAdd(TASKINFO_RUNNING_ALTITUDE, taskHandle); + return 0; + } + return -1; } /** @@ -88,12 +92,28 @@ int32_t AltitudeStart() */ int32_t AltitudeInitialize() { +#ifdef MODULE_Altitude_BUILTIN + altitudeEnabled = 1; +#else + HwSettingsInitialize(); + uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM]; + HwSettingsOptionalModulesGet(optionalModules); + if (optionalModules[HWSETTINGS_OPTIONALMODULES_ALTITUDE] == HWSETTINGS_OPTIONALMODULES_ENABLED) { + altitudeEnabled = 1; + } else { + altitudeEnabled = 0; + } +#endif // init down-sampling data alt_ds_temp = 0; alt_ds_pres = 0; alt_ds_count = 0; +<<<<<<< HEAD +======= + +>>>>>>> next return 0; } MODULE_INITCALL(AltitudeInitialize, AltitudeStart) @@ -144,19 +164,28 @@ static void altitudeTask(void *parameters) #endif // Update the temperature data PIOS_BMP085_StartADC(TemperatureConv); +#ifdef PIOS_BMP085_HAS_GPIOS xSemaphoreTake(PIOS_BMP085_EOC, portMAX_DELAY); +#else + vTaskDelay(5 / portTICK_RATE_MS); +#endif PIOS_BMP085_ReadADC(); alt_ds_temp += PIOS_BMP085_GetTemperature(); // Update the pressure data PIOS_BMP085_StartADC(PressureConv); +#ifdef PIOS_BMP085_HAS_GPIOS xSemaphoreTake(PIOS_BMP085_EOC, portMAX_DELAY); +#else + vTaskDelay(26 / portTICK_RATE_MS); +#endif PIOS_BMP085_ReadADC(); alt_ds_pres += PIOS_BMP085_GetPressure(); if (++alt_ds_count >= alt_ds_size) { alt_ds_count = 0; +<<<<<<< HEAD // Convert from 1/10ths of degC to degC data.Temperature = alt_ds_temp / (10.0 * alt_ds_size); @@ -173,6 +202,24 @@ static void altitudeTask(void *parameters) BaroAltitudeSet(&data); } +======= + + // Convert from 1/10ths of degC to degC + data.Temperature = alt_ds_temp / (10.0 * alt_ds_size); + alt_ds_temp = 0; + + // Convert from Pa to kPa + data.Pressure = alt_ds_pres / (1000.0f * alt_ds_size); + alt_ds_pres = 0; + + // Compute the current altitude (all pressures in kPa) + data.Altitude = 44330.0 * (1.0 - powf((data.Pressure / (BMP085_P0 / 1000.0)), (1.0 / 5.255))); + + // Update the AltitudeActual UAVObject + BaroAltitudeSet(&data); + } + +>>>>>>> next // Delay until it is time to read the next sample vTaskDelayUntil(&lastSysTime, UPDATE_PERIOD / portTICK_RATE_MS); } diff --git a/flight/Modules/Attitude/attitude.c b/flight/Modules/Attitude/attitude.c index 9e188877e..a156d6d0c 100644 --- a/flight/Modules/Attitude/attitude.c +++ b/flight/Modules/Attitude/attitude.c @@ -54,6 +54,7 @@ #include "attitudeactual.h" #include "attitudesettings.h" #include "flightstatus.h" +#include "manualcontrolcommand.h" #include "CoordinateConversions.h" #include "pios_flash_w25x.h" @@ -91,18 +92,28 @@ static int8_t rotate = 0; static bool zero_during_arming = false; static bool bias_correct_gyro = true; +// For running trim flights +static volatile bool trim_requested = false; +static volatile int32_t trim_accels[3]; +static volatile int32_t trim_samples; +int32_t const MAX_TRIM_FLIGHT_SAMPLES = 65535; + +#define GRAV 9.81f +#define ACCEL_SCALE (GRAV * 0.004f) +/* 0.004f is gravity / LSB */ + /** * Initialise the module, called on startup * \returns 0 on success or -1 if initialisation failed */ int32_t AttitudeStart(void) { - + // Start main task xTaskCreate(AttitudeTask, (signed char *)"Attitude", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle); TaskMonitorAdd(TASKINFO_RUNNING_ATTITUDE, taskHandle); PIOS_WDG_RegisterFlag(PIOS_WDG_ATTITUDE); - + return 0; } @@ -115,7 +126,7 @@ int32_t AttitudeInitialize(void) AttitudeActualInitialize(); AttitudeRawInitialize(); AttitudeSettingsInitialize(); - + // Initialize quaternion AttitudeActualData attitude; AttitudeActualGet(&attitude); @@ -124,12 +135,12 @@ int32_t AttitudeInitialize(void) attitude.q3 = 0; attitude.q4 = 0; AttitudeActualSet(&attitude); - + // Cannot trust the values to init right above if BL runs gyro_correct_int[0] = 0; gyro_correct_int[1] = 0; gyro_correct_int[2] = 0; - + q[0] = 1; q[1] = 0; q[2] = 0; @@ -137,17 +148,19 @@ int32_t AttitudeInitialize(void) for(uint8_t i = 0; i < 3; i++) for(uint8_t j = 0; j < 3; j++) R[i][j] = 0; - + + trim_requested = false; + // Create queue for passing gyro data, allow 2 back samples in case gyro_queue = xQueueCreate(1, sizeof(float) * 4); if(gyro_queue == NULL) return -1; - - + + PIOS_ADC_SetQueue(gyro_queue); - + AttitudeSettingsConnectCallback(&settingsUpdatedCb); - + return 0; } @@ -160,9 +173,9 @@ static void AttitudeTask(void *parameters) { uint8_t init = 0; AlarmsClear(SYSTEMALARMS_ALARM_ATTITUDE); - + PIOS_ADC_Config((PIOS_ADC_RATE / 1000.0f) * UPDATE_RATE); - + // Keep flash CS pin high while talking accel PIOS_FLASH_DISABLE; PIOS_ADXL345_Init(); @@ -175,13 +188,13 @@ static void AttitudeTask(void *parameters) // Force settings update to make sure rotation loaded settingsUpdatedCb(AttitudeSettingsHandle()); - + // Main task loop while (1) { - + FlightStatusData flightStatus; FlightStatusGet(&flightStatus); - + if((xTaskGetTickCount() < 7000) && (xTaskGetTickCount() > 1000)) { // For first 7 seconds use accels to get gyro bias accelKp = 1; @@ -201,9 +214,9 @@ static void AttitudeTask(void *parameters) AttitudeSettingsYawBiasRateGet(&yawBiasRate); init = 1; } - + PIOS_WDG_UpdateFlag(PIOS_WDG_ATTITUDE); - + AttitudeRawData attitudeRaw; AttitudeRawGet(&attitudeRaw); if(updateSensors(&attitudeRaw) != 0) @@ -214,7 +227,7 @@ static void AttitudeTask(void *parameters) AttitudeRawSet(&attitudeRaw); AlarmsClear(SYSTEMALARMS_ALARM_ATTITUDE); } - + } } @@ -227,22 +240,22 @@ static int8_t updateSensors(AttitudeRawData * attitudeRaw) { struct pios_adxl345_data accel_data; float gyro[4]; - + // Only wait the time for two nominal updates before setting an alarm if(xQueueReceive(gyro_queue, (void * const) gyro, UPDATE_RATE * 2) == errQUEUE_EMPTY) { AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE, SYSTEMALARMS_ALARM_ERROR); return -1; } - + // No accel data available if(PIOS_ADXL345_FifoElements() == 0) return -1; - + // First sample is temperature attitudeRaw->gyros[ATTITUDERAW_GYROS_X] = -(gyro[1] - GYRO_NEUTRAL) * gyroGain; attitudeRaw->gyros[ATTITUDERAW_GYROS_Y] = (gyro[2] - GYRO_NEUTRAL) * gyroGain; attitudeRaw->gyros[ATTITUDERAW_GYROS_Z] = -(gyro[3] - GYRO_NEUTRAL) * gyroGain; - + int32_t x = 0; int32_t y = 0; int32_t z = 0; @@ -259,7 +272,7 @@ static int8_t updateSensors(AttitudeRawData * attitudeRaw) attitudeRaw->temperature[ATTITUDERAW_TEMPERATURE_ACCEL] = i; float accel[3] = {(float) x / i, (float) y / i, (float) z / i}; - + if(rotate) { // TODO: rotate sensors too so stabilization is well behaved float vec_out[3]; @@ -276,19 +289,37 @@ static int8_t updateSensors(AttitudeRawData * attitudeRaw) attitudeRaw->accels[1] = accel[1]; attitudeRaw->accels[2] = accel[2]; } - + + if (trim_requested) { + if (trim_samples >= MAX_TRIM_FLIGHT_SAMPLES) { + trim_requested = false; + } else { + uint8_t armed; + float throttle; + FlightStatusArmedGet(&armed); + ManualControlCommandThrottleGet(&throttle); // Until flight status indicates airborne + if ((armed == FLIGHTSTATUS_ARMED_ARMED) && (throttle > 0)) { + trim_samples++; + // Store the digitally scaled version since that is what we use for bias + trim_accels[0] += attitudeRaw->accels[ATTITUDERAW_ACCELS_X]; + trim_accels[1] += attitudeRaw->accels[ATTITUDERAW_ACCELS_Y]; + trim_accels[2] += attitudeRaw->accels[ATTITUDERAW_ACCELS_Z]; + } + } + } + // Scale accels and correct bias - attitudeRaw->accels[ATTITUDERAW_ACCELS_X] = (attitudeRaw->accels[ATTITUDERAW_ACCELS_X] - accelbias[0]) * 0.004f * 9.81f; - attitudeRaw->accels[ATTITUDERAW_ACCELS_Y] = (attitudeRaw->accels[ATTITUDERAW_ACCELS_Y] - accelbias[1]) * 0.004f * 9.81f; - attitudeRaw->accels[ATTITUDERAW_ACCELS_Z] = (attitudeRaw->accels[ATTITUDERAW_ACCELS_Z] - accelbias[2]) * 0.004f * 9.81f; - + attitudeRaw->accels[ATTITUDERAW_ACCELS_X] = (attitudeRaw->accels[ATTITUDERAW_ACCELS_X] - accelbias[0]) * ACCEL_SCALE; + attitudeRaw->accels[ATTITUDERAW_ACCELS_Y] = (attitudeRaw->accels[ATTITUDERAW_ACCELS_Y] - accelbias[1]) * ACCEL_SCALE; + attitudeRaw->accels[ATTITUDERAW_ACCELS_Z] = (attitudeRaw->accels[ATTITUDERAW_ACCELS_Z] - accelbias[2]) * ACCEL_SCALE; + if(bias_correct_gyro) { // Applying integral component here so it can be seen on the gyros and correct bias attitudeRaw->gyros[ATTITUDERAW_GYROS_X] += gyro_correct_int[0]; attitudeRaw->gyros[ATTITUDERAW_GYROS_Y] += gyro_correct_int[1]; attitudeRaw->gyros[ATTITUDERAW_GYROS_Z] += gyro_correct_int[2]; } - + // Because most crafts wont get enough information from gravity to zero yaw gyro, we try // and make it average zero (weakly) gyro_correct_int[2] += - attitudeRaw->gyros[ATTITUDERAW_GYROS_Z] * yawBiasRate; @@ -301,45 +332,45 @@ static void updateAttitude(AttitudeRawData * attitudeRaw) float dT; portTickType thisSysTime = xTaskGetTickCount(); static portTickType lastSysTime = 0; - + dT = (thisSysTime == lastSysTime) ? 0.001 : (portMAX_DELAY & (thisSysTime - lastSysTime)) / portTICK_RATE_MS / 1000.0f; lastSysTime = thisSysTime; - + // Bad practice to assume structure order, but saves memory float gyro[3]; gyro[0] = attitudeRaw->gyros[0]; gyro[1] = attitudeRaw->gyros[1]; gyro[2] = attitudeRaw->gyros[2]; - + { float * accels = attitudeRaw->accels; float grot[3]; float accel_err[3]; - + // Rotate gravity to body frame and cross with accels grot[0] = -(2 * (q[1] * q[3] - q[0] * q[2])); grot[1] = -(2 * (q[2] * q[3] + q[0] * q[1])); grot[2] = -(q[0] * q[0] - q[1]*q[1] - q[2]*q[2] + q[3]*q[3]); CrossProduct((const float *) accels, (const float *) grot, accel_err); - + // Account for accel magnitude float accel_mag = sqrt(accels[0]*accels[0] + accels[1]*accels[1] + accels[2]*accels[2]); accel_err[0] /= accel_mag; accel_err[1] /= accel_mag; accel_err[2] /= accel_mag; - + // Accumulate integral of error. Scale here so that units are (deg/s) but Ki has units of s gyro_correct_int[0] += accel_err[0] * accelKi; gyro_correct_int[1] += accel_err[1] * accelKi; - - //gyro_correct_int[2] += accel_err[2] * settings.AccelKI * dT; - + + //gyro_correct_int[2] += accel_err[2] * accelKi; + // Correct rates based on error, integral component dealt with in updateSensors gyro[0] += accel_err[0] * accelKp / dT; gyro[1] += accel_err[1] * accelKp / dT; gyro[2] += accel_err[2] * accelKp / dT; } - + { // scoping variables to save memory // Work out time derivative from INSAlgo writeup // Also accounts for the fact that gyros are in deg/s @@ -348,7 +379,7 @@ static void updateAttitude(AttitudeRawData * attitudeRaw) qdot[1] = (q[0] * gyro[0] - q[3] * gyro[1] + q[2] * gyro[2]) * dT * M_PI / 180 / 2; qdot[2] = (q[3] * gyro[0] + q[0] * gyro[1] - q[1] * gyro[2]) * dT * M_PI / 180 / 2; qdot[3] = (-q[2] * gyro[0] + q[1] * gyro[1] + q[0] * gyro[2]) * dT * M_PI / 180 / 2; - + // Take a time step q[0] = q[0] + qdot[0]; q[1] = q[1] + qdot[1]; @@ -362,14 +393,14 @@ static void updateAttitude(AttitudeRawData * attitudeRaw) q[3] = -q[3]; } } - + // Renomalize float qmag = sqrt(q[0]*q[0] + q[1]*q[1] + q[2]*q[2] + q[3]*q[3]); q[0] = q[0] / qmag; q[1] = q[1] / qmag; q[2] = q[2] / qmag; q[3] = q[3] / qmag; - + // If quaternion has become inappropriately short or is nan reinit. // THIS SHOULD NEVER ACTUALLY HAPPEN if((fabs(qmag) < 1e-3) || (qmag != qmag)) { @@ -378,44 +409,44 @@ static void updateAttitude(AttitudeRawData * attitudeRaw) q[2] = 0; q[3] = 0; } - + AttitudeActualData attitudeActual; AttitudeActualGet(&attitudeActual); - + quat_copy(q, &attitudeActual.q1); - + // Convert into eueler degrees (makes assumptions about RPY order) Quaternion2RPY(&attitudeActual.q1,&attitudeActual.Roll); - + AttitudeActualSet(&attitudeActual); } static void settingsUpdatedCb(UAVObjEvent * objEv) { AttitudeSettingsData attitudeSettings; AttitudeSettingsGet(&attitudeSettings); - - + + accelKp = attitudeSettings.AccelKp; accelKi = attitudeSettings.AccelKi; yawBiasRate = attitudeSettings.YawBiasRate; gyroGain = attitudeSettings.GyroGain; - + zero_during_arming = attitudeSettings.ZeroDuringArming == ATTITUDESETTINGS_ZERODURINGARMING_TRUE; bias_correct_gyro = attitudeSettings.BiasCorrectGyro == ATTITUDESETTINGS_BIASCORRECTGYRO_TRUE; - + accelbias[0] = attitudeSettings.AccelBias[ATTITUDESETTINGS_ACCELBIAS_X]; accelbias[1] = attitudeSettings.AccelBias[ATTITUDESETTINGS_ACCELBIAS_Y]; accelbias[2] = attitudeSettings.AccelBias[ATTITUDESETTINGS_ACCELBIAS_Z]; - + gyro_correct_int[0] = attitudeSettings.GyroBias[ATTITUDESETTINGS_GYROBIAS_X] / 100.0f; gyro_correct_int[1] = attitudeSettings.GyroBias[ATTITUDESETTINGS_GYROBIAS_Y] / 100.0f; gyro_correct_int[2] = attitudeSettings.GyroBias[ATTITUDESETTINGS_GYROBIAS_Z] / 100.0f; - + // Indicates not to expend cycles on rotation if(attitudeSettings.BoardRotation[0] == 0 && attitudeSettings.BoardRotation[1] == 0 && attitudeSettings.BoardRotation[2] == 0) { rotate = 0; - + // Shouldn't be used but to be safe float rotationQuat[4] = {1,0,0,0}; Quaternion2R(rotationQuat, R); @@ -428,8 +459,25 @@ static void settingsUpdatedCb(UAVObjEvent * objEv) { Quaternion2R(rotationQuat, R); rotate = 1; } + + if (attitudeSettings.TrimFlight == ATTITUDESETTINGS_TRIMFLIGHT_START) { + trim_accels[0] = 0; + trim_accels[1] = 0; + trim_accels[2] = 0; + trim_samples = 0; + trim_requested = true; + } else if (attitudeSettings.TrimFlight == ATTITUDESETTINGS_TRIMFLIGHT_LOAD) { + trim_requested = false; + attitudeSettings.AccelBias[ATTITUDESETTINGS_ACCELBIAS_X] = trim_accels[0] / trim_samples; + attitudeSettings.AccelBias[ATTITUDESETTINGS_ACCELBIAS_Y] = trim_accels[1] / trim_samples; + // Z should average -grav + attitudeSettings.AccelBias[ATTITUDESETTINGS_ACCELBIAS_Z] = trim_accels[2] / trim_samples + GRAV / ACCEL_SCALE; + attitudeSettings.TrimFlight = ATTITUDESETTINGS_TRIMFLIGHT_NORMAL; + AttitudeSettingsSet(&attitudeSettings); + } else + trim_requested = false; } /** - * @} - * @} - */ + * @} + * @} + */ diff --git a/flight/Modules/CameraStab/camerastab.c b/flight/Modules/CameraStab/camerastab.c index 770ff7ab6..4e83ae33b 100644 --- a/flight/Modules/CameraStab/camerastab.c +++ b/flight/Modules/CameraStab/camerastab.c @@ -61,10 +61,15 @@ // Private types // Private variables +static struct CameraStab_data { + portTickType lastSysTime; + float inputs[CAMERASTABSETTINGS_INPUT_NUMELEM]; + float inputs_filtered[CAMERASTABSETTINGS_INPUT_NUMELEM]; +} *csd; // Private functions static void attitudeUpdated(UAVObjEvent* ev); -static float bound(float val); +static float bound(float val, float limit); /** * Initialise the module, called on startup @@ -72,9 +77,11 @@ static float bound(float val); */ int32_t CameraStabInitialize(void) { - static UAVObjEvent ev; - bool cameraStabEnabled; + +#ifdef MODULE_CameraStab_BUILTIN + cameraStabEnabled = true; +#else uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM]; HwSettingsInitialize(); @@ -84,18 +91,28 @@ int32_t CameraStabInitialize(void) cameraStabEnabled = true; else cameraStabEnabled = false; +#endif if (cameraStabEnabled) { + // allocate and initialize the static data storage only if module is enabled + csd = (struct CameraStab_data *) pvPortMalloc(sizeof(struct CameraStab_data)); + if (!csd) + return -1; + + // make sure that all inputs[] and inputs_filtered[] are zeroed + memset(csd, 0, sizeof(struct CameraStab_data)); + csd->lastSysTime = xTaskGetTickCount(); + AttitudeActualInitialize(); - - ev.obj = AttitudeActualHandle(); - ev.instId = 0; - ev.event = 0; - CameraStabSettingsInitialize(); CameraDesiredInitialize(); + UAVObjEvent ev = { + .obj = AttitudeActualHandle(), + .instId = 0, + .event = 0, + }; EventPeriodicCallbackCreate(&ev, attitudeUpdated, SAMPLE_PERIOD_MS / portTICK_RATE_MS); return 0; @@ -117,47 +134,68 @@ static void attitudeUpdated(UAVObjEvent* ev) if (ev->obj != AttitudeActualHandle()) return; - float attitude; - float output; AccessoryDesiredData accessory; CameraStabSettingsData cameraStab; CameraStabSettingsGet(&cameraStab); - // Read any input channels - float inputs[3] = {0,0,0}; - if(cameraStab.Inputs[CAMERASTABSETTINGS_INPUTS_ROLL] != CAMERASTABSETTINGS_INPUTS_NONE) { - if(AccessoryDesiredInstGet(cameraStab.Inputs[CAMERASTABSETTINGS_INPUTS_ROLL] - CAMERASTABSETTINGS_INPUTS_ACCESSORY0, &accessory) == 0) - inputs[0] = accessory.AccessoryVal * cameraStab.InputRange[CAMERASTABSETTINGS_INPUTRANGE_ROLL]; - } - if(cameraStab.Inputs[CAMERASTABSETTINGS_INPUTS_PITCH] != CAMERASTABSETTINGS_INPUTS_NONE) { - if(AccessoryDesiredInstGet(cameraStab.Inputs[CAMERASTABSETTINGS_INPUTS_PITCH] - CAMERASTABSETTINGS_INPUTS_ACCESSORY0, &accessory) == 0) - inputs[1] = accessory.AccessoryVal * cameraStab.InputRange[CAMERASTABSETTINGS_INPUTRANGE_PITCH]; - } - if(cameraStab.Inputs[CAMERASTABSETTINGS_INPUTS_YAW] != CAMERASTABSETTINGS_INPUTS_NONE) { - if(AccessoryDesiredInstGet(cameraStab.Inputs[CAMERASTABSETTINGS_INPUTS_YAW] - CAMERASTABSETTINGS_INPUTS_ACCESSORY0, &accessory) == 0) - inputs[2] = accessory.AccessoryVal * cameraStab.InputRange[CAMERASTABSETTINGS_INPUTRANGE_YAW]; + // Check how long since last update, time delta between calls in ms + portTickType thisSysTime = xTaskGetTickCount(); + float dT = (thisSysTime > csd->lastSysTime) ? + (thisSysTime - csd->lastSysTime) / portTICK_RATE_MS : + (float)SAMPLE_PERIOD_MS / 1000.0f; + csd->lastSysTime = thisSysTime; + + // Read any input channels and apply LPF + for (uint8_t i = 0; i < CAMERASTABSETTINGS_INPUT_NUMELEM; i++) { + if (cameraStab.Input[i] != CAMERASTABSETTINGS_INPUT_NONE) { + if (AccessoryDesiredInstGet(cameraStab.Input[i] - CAMERASTABSETTINGS_INPUT_ACCESSORY0, &accessory) == 0) { + float input_rate; + switch (cameraStab.StabilizationMode[i]) { + case CAMERASTABSETTINGS_STABILIZATIONMODE_ATTITUDE: + csd->inputs[i] = accessory.AccessoryVal * cameraStab.InputRange[i]; + break; + case CAMERASTABSETTINGS_STABILIZATIONMODE_AXISLOCK: + input_rate = accessory.AccessoryVal * cameraStab.InputRate[i]; + if (fabs(input_rate) > cameraStab.MaxAxisLockRate) + csd->inputs[i] = bound(csd->inputs[i] + input_rate * dT / 1000.0f, cameraStab.InputRange[i]); + break; + default: + PIOS_Assert(0); + } + + // bypass LPF calculation if ResponseTime is zero + float rt = (float)cameraStab.ResponseTime[i]; + if (rt) + csd->inputs_filtered[i] = (rt / (rt + dT)) * csd->inputs_filtered[i] + + (dT / (rt + dT)) * csd->inputs[i]; + else + csd->inputs_filtered[i] = csd->inputs[i]; + } + } } // Set output channels + float attitude; + float output; + AttitudeActualRollGet(&attitude); - output = bound((attitude + inputs[0]) / cameraStab.OutputRange[CAMERASTABSETTINGS_OUTPUTRANGE_ROLL]); + output = bound((attitude + csd->inputs_filtered[CAMERASTABSETTINGS_INPUT_ROLL]) / cameraStab.OutputRange[CAMERASTABSETTINGS_OUTPUTRANGE_ROLL], 1.0f); CameraDesiredRollSet(&output); AttitudeActualPitchGet(&attitude); - output = bound((attitude + inputs[1]) / cameraStab.OutputRange[CAMERASTABSETTINGS_OUTPUTRANGE_PITCH]); + output = bound((attitude + csd->inputs_filtered[CAMERASTABSETTINGS_INPUT_PITCH]) / cameraStab.OutputRange[CAMERASTABSETTINGS_OUTPUTRANGE_PITCH], 1.0f); CameraDesiredPitchSet(&output); AttitudeActualYawGet(&attitude); - output = bound((attitude + inputs[2]) / cameraStab.OutputRange[CAMERASTABSETTINGS_OUTPUTRANGE_YAW]); + output = bound((attitude + csd->inputs_filtered[CAMERASTABSETTINGS_INPUT_YAW]) / cameraStab.OutputRange[CAMERASTABSETTINGS_OUTPUTRANGE_YAW], 1.0f); CameraDesiredYawSet(&output); - } -float bound(float val) +float bound(float val, float limit) { - return (val > 1) ? 1 : - (val < -1) ? -1 : + return (val > limit) ? limit : + (val < -limit) ? -limit : val; } /** diff --git a/flight/Modules/ComUsbBridge/ComUsbBridge.c b/flight/Modules/ComUsbBridge/ComUsbBridge.c new file mode 100644 index 000000000..678e7039d --- /dev/null +++ b/flight/Modules/ComUsbBridge/ComUsbBridge.c @@ -0,0 +1,199 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotModules OpenPilot Modules + * @{ + * @addtogroup ComUsbBridgeModule Com Port to USB VCP Bridge Module + * @brief Bridge Com and USB VCP ports + * @{ + * + * @file ComUsbBridge.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. + * @brief Bridges selected Com Port to the USB VCP emulated serial port + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +// **************** + +#include "openpilot.h" +#include "hwsettings.h" + +#include + +// **************** +// Private functions + +static void com2UsbBridgeTask(void *parameters); +static void usb2ComBridgeTask(void *parameters); +static void updateSettings(); + +// **************** +// Private constants + +#define STACK_SIZE_BYTES 280 +#define TASK_PRIORITY (tskIDLE_PRIORITY + 1) + +#define BRIDGE_BUF_LEN 10 + +// **************** +// Private variables + +static xTaskHandle com2UsbBridgeTaskHandle; +static xTaskHandle usb2ComBridgeTaskHandle; + +static uint8_t * com2usb_buf; +static uint8_t * usb2com_buf; + +static uint32_t usart_port; +static uint32_t vcp_port; + +static bool bridge_enabled = false; + +/** + * Initialise the module + * \return -1 if initialisation failed + * \return 0 on success + */ + +static int32_t comUsbBridgeStart(void) +{ + if (bridge_enabled) { + // Start tasks + xTaskCreate(com2UsbBridgeTask, (signed char *)"Com2UsbBridge", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &com2UsbBridgeTaskHandle); + TaskMonitorAdd(TASKINFO_RUNNING_COM2USBBRIDGE, com2UsbBridgeTaskHandle); + xTaskCreate(usb2ComBridgeTask, (signed char *)"Usb2ComBridge", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &usb2ComBridgeTaskHandle); + TaskMonitorAdd(TASKINFO_RUNNING_USB2COMBRIDGE, usb2ComBridgeTaskHandle); + return 0; + } + + return -1; +} +/** + * Initialise the module + * \return -1 if initialisation failed + * \return 0 on success + */ +static int32_t comUsbBridgeInitialize(void) +{ + // TODO: Get from settings object + usart_port = PIOS_COM_BRIDGE; + vcp_port = PIOS_COM_VCP; + +#ifdef MODULE_ComUsbBridge_BUILTIN + bridge_enabled = true; +#else + HwSettingsInitialize(); + uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM]; + + HwSettingsOptionalModulesGet(optionalModules); + + if (usart_port && vcp_port && + (optionalModules[HWSETTINGS_OPTIONALMODULES_COMUSBBRIDGE] == HWSETTINGS_OPTIONALMODULES_ENABLED)) + bridge_enabled = true; + else + bridge_enabled = false; +#endif + + if (bridge_enabled) { + com2usb_buf = pvPortMalloc(BRIDGE_BUF_LEN); + PIOS_Assert(com2usb_buf); + usb2com_buf = pvPortMalloc(BRIDGE_BUF_LEN); + PIOS_Assert(usb2com_buf); + + updateSettings(); + } + + return 0; +} +MODULE_INITCALL(comUsbBridgeInitialize, comUsbBridgeStart) + +/** + * Main task. It does not return. + */ + +static void com2UsbBridgeTask(void *parameters) +{ + /* Handle usart -> vcp direction */ + volatile uint32_t tx_errors = 0; + while (1) { + uint32_t rx_bytes; + + rx_bytes = PIOS_COM_ReceiveBuffer(usart_port, com2usb_buf, BRIDGE_BUF_LEN, 500); + if (rx_bytes > 0) { + /* Bytes available to transfer */ + if (PIOS_COM_SendBuffer(vcp_port, com2usb_buf, rx_bytes) != rx_bytes) { + /* Error on transmit */ + tx_errors++; + } + } + } +} + +static void usb2ComBridgeTask(void * parameters) +{ + /* Handle vcp -> usart direction */ + volatile uint32_t tx_errors = 0; + while (1) { + uint32_t rx_bytes; + + rx_bytes = PIOS_COM_ReceiveBuffer(vcp_port, usb2com_buf, BRIDGE_BUF_LEN, 500); + if (rx_bytes > 0) { + /* Bytes available to transfer */ + if (PIOS_COM_SendBuffer(usart_port, usb2com_buf, rx_bytes) != rx_bytes) { + /* Error on transmit */ + tx_errors++; + } + } + } +} + + +static void updateSettings() +{ + if (usart_port) { + + // Retrieve settings + uint8_t speed; + HwSettingsComUsbBridgeSpeedGet(&speed); + + // Set port speed + switch (speed) { + case HWSETTINGS_COMUSBBRIDGESPEED_2400: + PIOS_COM_ChangeBaud(usart_port, 2400); + break; + case HWSETTINGS_COMUSBBRIDGESPEED_4800: + PIOS_COM_ChangeBaud(usart_port, 4800); + break; + case HWSETTINGS_COMUSBBRIDGESPEED_9600: + PIOS_COM_ChangeBaud(usart_port, 9600); + break; + case HWSETTINGS_COMUSBBRIDGESPEED_19200: + PIOS_COM_ChangeBaud(usart_port, 19200); + break; + case HWSETTINGS_COMUSBBRIDGESPEED_38400: + PIOS_COM_ChangeBaud(usart_port, 38400); + break; + case HWSETTINGS_COMUSBBRIDGESPEED_57600: + PIOS_COM_ChangeBaud(usart_port, 57600); + break; + case HWSETTINGS_COMUSBBRIDGESPEED_115200: + PIOS_COM_ChangeBaud(usart_port, 115200); + break; + } + } +} diff --git a/flight/Modules/Fault/Fault.c b/flight/Modules/Fault/Fault.c new file mode 100644 index 000000000..868330739 --- /dev/null +++ b/flight/Modules/Fault/Fault.c @@ -0,0 +1,135 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotModules OpenPilot Modules + * @{ + * @addtogroup FaultModule Fault Module + * @brief Insert various fault conditions for testing + * @{ + * + * @file Fault.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Fault module, inserts faults for testing + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +// **************** + +#include "openpilot.h" +#include +#include "hwsettings.h" +#include "faultsettings.h" + +static bool module_enabled; +static uint8_t active_fault; + +static int32_t fault_initialize(void) +{ +#ifdef MODULE_Fault_BUILTIN + module_enabled = true; +#else + HwSettingsInitialize(); + uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM]; + + HwSettingsOptionalModulesGet(optionalModules); + + if (optionalModules[HWSETTINGS_OPTIONALMODULES_FAULT] == HWSETTINGS_OPTIONALMODULES_ENABLED) { + module_enabled = true; + } else { + module_enabled = false; + } +#endif + + /* Do this outside the module_enabled test so that it + * can be changed even when the module has been disabled. + * This is important so we can remove faults even when + * we've booted in BootFault recovery mode with all optional + * modules disabled. + */ + FaultSettingsInitialize(); + + if (module_enabled) { + FaultSettingsActivateFaultGet(&active_fault); + + switch (active_fault) { + case FAULTSETTINGS_ACTIVATEFAULT_MODULEINITASSERT: + /* Simulate an assert during module init */ + PIOS_Assert(0); + break; + case FAULTSETTINGS_ACTIVATEFAULT_INITOUTOFMEMORY: + /* Leak all available memory */ + while (pvPortMalloc(10)) ; + break; + case FAULTSETTINGS_ACTIVATEFAULT_INITBUSERROR: + { + /* Force a bad access */ + uint32_t * bad_ptr = (uint32_t *)0xFFFFFFFF; + *bad_ptr = 0xAA55AA55; + } + break; + } + } + + return 0; +} + +static void fault_task(void *parameters); + +static int32_t fault_start(void) +{ + xTaskHandle fault_task_handle; + + if (module_enabled) { + switch (active_fault) { + case FAULTSETTINGS_ACTIVATEFAULT_RUNAWAYTASK: + case FAULTSETTINGS_ACTIVATEFAULT_TASKOUTOFMEMORY: + xTaskCreate(fault_task, + (signed char *)"Fault", + configMINIMAL_STACK_SIZE, + NULL, + configMAX_PRIORITIES-1, + &fault_task_handle); + return 0; + break; + } + } + return -1; +} +MODULE_INITCALL(fault_initialize, fault_start) + +static void fault_task(void *parameters) +{ + switch (active_fault) { + case FAULTSETTINGS_ACTIVATEFAULT_RUNAWAYTASK: + /* Consume all realtime, not letting the systemtask run */ + while(1); + break; + case FAULTSETTINGS_ACTIVATEFAULT_TASKOUTOFMEMORY: + /* Leak all available memory and then sleep */ + while (pvPortMalloc(10)) ; + while (1) { + vTaskDelay(1000); + } + break; + } +} + +/** + * @} + * @} + */ diff --git a/flight/Modules/GPS/GPS.c b/flight/Modules/GPS/GPS.c index d7b202346..716e47aa3 100644 --- a/flight/Modules/GPS/GPS.c +++ b/flight/Modules/GPS/GPS.c @@ -121,6 +121,9 @@ int32_t GPSInitialize(void) { gpsPort = PIOS_COM_GPS; +#ifdef MODULE_GPS_BUILTIN + gpsEnabled = true; +#else HwSettingsInitialize(); uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM]; @@ -130,6 +133,7 @@ int32_t GPSInitialize(void) gpsEnabled = true; else gpsEnabled = false; +#endif if (gpsPort && gpsEnabled) { GPSPositionInitialize(); diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index a787a2a82..8a84631b8 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -49,7 +49,6 @@ #include "watchdogstatus.h" #include "taskmonitor.h" - // Private constants #define SYSTEM_UPDATE_PERIOD_MS 1000 #define LED_BLINK_RATE_HZ 5 @@ -115,8 +114,10 @@ int32_t SystemModInitialize(void) SystemStatsInitialize(); FlightStatusInitialize(); ObjectPersistenceInitialize(); -#if defined(DIAGNOSTICS) +#if defined(DIAG_TASKS) TaskInfoInitialize(); +#endif +#if defined(DIAGNOSTICS) I2CStatsInitialize(); WatchdogStatusInitialize(); #endif @@ -135,7 +136,20 @@ static void systemTask(void *parameters) portTickType lastSysTime; /* create all modules thread */ - MODULE_TASKCREATE_ALL + MODULE_TASKCREATE_ALL; + + if (mallocFailed) { + /* We failed to malloc during task creation, + * system behaviour is undefined. Reset and let + * the BootFault code recover for us. + */ + PIOS_SYS_Reset(); + } + +#if defined(PIOS_INCLUDE_IAP) + /* Record a successful boot */ + PIOS_IAP_WriteBootCount(0); +#endif // Initialize vars idleCounter = 0; @@ -156,8 +170,11 @@ static void systemTask(void *parameters) updateI2Cstats(); updateWDGstats(); #endif + +#if defined(DIAG_TASKS) // Update the task status object TaskMonitorUpdateAll(); +#endif // Flash the heartbeat LED PIOS_LED_Toggle(LED1); diff --git a/flight/Modules/Telemetry/telemetry.c b/flight/Modules/Telemetry/telemetry.c index 57163c6e2..82a5867f2 100644 --- a/flight/Modules/Telemetry/telemetry.c +++ b/flight/Modules/Telemetry/telemetry.c @@ -133,7 +133,7 @@ int32_t TelemetryInitialize(void) updateSettings(); // Initialise UAVTalk - uavTalkCon = UAVTalkInitialize(&transmitData,256); + uavTalkCon = UAVTalkInitialize(&transmitData); // Create periodic event that will be used to update the telemetry stats txErrors = 0; @@ -308,12 +308,12 @@ static void telemetryRxTask(void *parameters) // Task loop while (1) { -#if defined(PIOS_INCLUDE_USB_HID) +#if defined(PIOS_INCLUDE_USB) // Determine input port (USB takes priority over telemetry port) - if (PIOS_USB_HID_CheckAvailable(0)) { + if (PIOS_USB_CheckAvailable(0) && PIOS_COM_TELEM_USB) { inputPort = PIOS_COM_TELEM_USB; } else -#endif /* PIOS_INCLUDE_USB_HID */ +#endif /* PIOS_INCLUDE_USB */ { inputPort = telemetryPort; } @@ -339,24 +339,25 @@ static void telemetryRxTask(void *parameters) * Transmit data buffer to the modem or USB port. * \param[in] data Data buffer to send * \param[in] length Length of buffer - * \return 0 Success + * \return -1 on failure + * \return number of bytes transmitted on success */ static int32_t transmitData(uint8_t * data, int32_t length) { uint32_t outputPort; // Determine input port (USB takes priority over telemetry port) -#if defined(PIOS_INCLUDE_USB_HID) - if (PIOS_USB_HID_CheckAvailable(0)) { +#if defined(PIOS_INCLUDE_USB) + if (PIOS_USB_CheckAvailable(0) && PIOS_COM_TELEM_USB) { outputPort = PIOS_COM_TELEM_USB; } else -#endif /* PIOS_INCLUDE_USB_HID */ +#endif /* PIOS_INCLUDE_USB */ { outputPort = telemetryPort; } if (outputPort) { - return PIOS_COM_SendBufferNonBlocking(outputPort, data, length); + return PIOS_COM_SendBuffer(outputPort, data, length); } else { return -1; } diff --git a/flight/OpenPilot/System/pios_usb_board_data.c b/flight/OpenPilot/System/pios_usb_board_data.c new file mode 100644 index 000000000..a6fa67abe --- /dev/null +++ b/flight/OpenPilot/System/pios_usb_board_data.c @@ -0,0 +1,120 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB_BOARD Board specific USB definitions + * @brief Board specific USB definitions + * @{ + * + * @file pios_usb_board_data.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Board specific USB definitions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "pios_usb_board_data.h" /* struct usb_*, USB_* */ +#include "pios_sys.h" /* PIOS_SYS_SerialNumberGet */ +#include "pios_usbhook.h" /* PIOS_USBHOOK_* */ + +static const uint8_t usb_product_id[20] = { + sizeof(usb_product_id), + USB_DESC_TYPE_STRING, + 'O', 0, + 'p', 0, + 'e', 0, + 'n', 0, + 'P', 0, + 'i', 0, + 'l', 0, + 'o', 0, + 't', 0, +}; + +static uint8_t usb_serial_number[52] = { + sizeof(usb_serial_number), + USB_DESC_TYPE_STRING, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0 +}; + +static const struct usb_string_langid usb_lang_id = { + .bLength = sizeof(usb_lang_id), + .bDescriptorType = USB_DESC_TYPE_STRING, + .bLangID = htousbs(USB_LANGID_ENGLISH_UK), +}; + +static const uint8_t usb_vendor_id[28] = { + sizeof(usb_vendor_id), + USB_DESC_TYPE_STRING, + 'o', 0, + 'p', 0, + 'e', 0, + 'n', 0, + 'p', 0, + 'i', 0, + 'l', 0, + 'o', 0, + 't', 0, + '.', 0, + 'o', 0, + 'r', 0, + 'g', 0 +}; + +int32_t PIOS_USB_BOARD_DATA_Init(void) +{ + /* Load device serial number into serial number string */ + uint8_t sn[25]; + PIOS_SYS_SerialNumberGet((char *)sn); + for (uint8_t i = 0; sn[i] != '\0' && (2 * i) < usb_serial_number[0]; i++) { + usb_serial_number[2 + 2 * i] = sn[i]; + } + + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_PRODUCT, (uint8_t *)&usb_product_id, sizeof(usb_product_id)); + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_SERIAL, (uint8_t *)&usb_serial_number, sizeof(usb_serial_number)); + + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_LANG, (uint8_t *)&usb_lang_id, sizeof(usb_lang_id)); + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_VENDOR, (uint8_t *)&usb_vendor_id, sizeof(usb_vendor_id)); + + return 0; +} + diff --git a/flight/PiOS/Boards/STM32103CB_CC_Rev1.h b/flight/PiOS/Boards/STM32103CB_CC_Rev1.h index 1a8a17c89..7773b9092 100644 --- a/flight/PiOS/Boards/STM32103CB_CC_Rev1.h +++ b/flight/PiOS/Boards/STM32103CB_CC_Rev1.h @@ -110,8 +110,15 @@ TIM4 | RC In 1 | Servo 3 | Servo 2 | Servo 1 // See also pios_board.c //------------------------ #define PIOS_I2C_MAX_DEVS 1 -extern uint32_t pios_i2c_main_adapter_id; -#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_main_adapter_id) +extern uint32_t pios_i2c_flexi_adapter_id; +#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_flexi_adapter_id) +#define PIOS_I2C_ESC_ADAPTER (pios_i2c_flexi_adapter_id) +#define PIOS_I2C_BMP085_ADAPTER (pios_i2c_flexi_adapter_id) + +//------------------------ +// PIOS_BMP085 +//------------------------ +#define PIOS_BMP085_OVERSAMPLING 3 //------------------------- // SPI @@ -141,6 +148,12 @@ extern uint32_t pios_com_gps_id; #define PIOS_COM_GPS (pios_com_gps_id) #endif /* PIOS_INCLUDE_GPS */ +extern uint32_t pios_com_bridge_id; +#define PIOS_COM_BRIDGE (pios_com_bridge_id) + +extern uint32_t pios_com_vcp_id; +#define PIOS_COM_VCP (pios_com_vcp_id) + extern uint32_t pios_com_telem_usb_id; #define PIOS_COM_TELEM_USB (pios_com_telem_usb_id) @@ -265,9 +278,11 @@ extern uint32_t pios_com_telem_usb_id; //------------------------- // USB //------------------------- -#define PIOS_USB_ENABLED 1 #define PIOS_USB_HID_MAX_DEVS 1 + +#define PIOS_USB_ENABLED 1 #define PIOS_USB_DETECT_GPIO_PORT GPIOC +#define PIOS_USB_MAX_DEVS 1 #define PIOS_USB_DETECT_GPIO_PIN GPIO_Pin_15 #define PIOS_USB_DETECT_EXTI_LINE EXTI_Line15 #define PIOS_IRQ_USB_PRIORITY PIOS_IRQ_PRIO_MID diff --git a/flight/PiOS/Boards/STM32103CB_PIPXTREME_Rev1.h b/flight/PiOS/Boards/STM32103CB_PIPXTREME_Rev1.h index 7027a42bd..b918ead67 100644 --- a/flight/PiOS/Boards/STM32103CB_PIPXTREME_Rev1.h +++ b/flight/PiOS/Boards/STM32103CB_PIPXTREME_Rev1.h @@ -393,12 +393,13 @@ extern uint32_t pios_com_telem_usb_id; #if defined(PIOS_INCLUDE_USB_HID) #define PIOS_USB_ENABLED 1 - #define PIOS_USB_HID_MAX_DEVS 1 + #define PIOS_USB_MAX_DEVS 1 #define PIOS_USB_DETECT_GPIO_PORT GPIO_IN_2_PORT #define PIOS_USB_DETECT_GPIO_PIN GPIO_IN_2_PIN #define PIOS_USB_DETECT_EXTI_LINE EXTI_Line4 #define PIOS_IRQ_USB_PRIORITY 8 #endif +#define PIOS_USB_HID_MAX_DEVS 1 // ***************************************************************** // RFM22 diff --git a/flight/PiOS/Boards/STM3210E_OP.h b/flight/PiOS/Boards/STM3210E_OP.h index c82bb8fe8..7099234c6 100644 --- a/flight/PiOS/Boards/STM3210E_OP.h +++ b/flight/PiOS/Boards/STM3210E_OP.h @@ -115,10 +115,13 @@ TIM8 | Servo 5 | Servo 6 | Servo 7 | Servo 8 #define PIOS_I2C_MAX_DEVS 1 extern uint32_t pios_i2c_main_adapter_id; #define PIOS_I2C_MAIN_ADAPTER (pios_i2c_main_adapter_id) +#define PIOS_I2C_ESC_ADAPTER (pios_i2c_main_adapter_id) +#define PIOS_I2C_BMP085_ADAPTER (pios_i2c_main_adapter_id) //------------------------ // PIOS_BMP085 //------------------------ +#define PIOS_BMP085_HAS_GPIOS #define PIOS_BMP085_EOC_GPIO_PORT GPIOC #define PIOS_BMP085_EOC_GPIO_PIN GPIO_Pin_15 #define PIOS_BMP085_EOC_PORT_SOURCE GPIO_PortSourceGPIOC @@ -309,8 +312,9 @@ extern uint32_t pios_com_aux_id; // USB //------------------------- #define PIOS_USB_ENABLED 1 -#define PIOS_USB_HID_MAX_DEVS 1 #define PIOS_USB_DETECT_GPIO_PORT GPIOC +#define PIOS_USB_MAX_DEVS 1 +#define PIOS_USB_HID_MAX_DEVS 1 #define PIOS_USB_DETECT_GPIO_PIN GPIO_Pin_4 #define PIOS_USB_DETECT_EXTI_LINE EXTI_Line4 #define PIOS_IRQ_USB_PRIORITY PIOS_IRQ_PRIO_MID diff --git a/flight/PiOS/Boards/STM32F4xx_Revolution.h b/flight/PiOS/Boards/STM32F4xx_Revolution.h index 24c5b99c8..fa4483918 100644 --- a/flight/PiOS/Boards/STM32F4xx_Revolution.h +++ b/flight/PiOS/Boards/STM32F4xx_Revolution.h @@ -5,8 +5,7 @@ * @addtogroup OpenPilotCore OpenPilot Core * @{ * @file pios_board.h - * @author David "Buzz" Carlson (buzz@chebuzz.com) - * The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief Defines board hardware for the OpenPilot Version 1.1 hardware. * @see The GNU Public License (GPL) Version 3 * diff --git a/flight/PiOS/Common/pios_com.c b/flight/PiOS/Common/pios_com.c index e7fba8867..20e32ffd3 100644 --- a/flight/PiOS/Common/pios_com.c +++ b/flight/PiOS/Common/pios_com.c @@ -8,7 +8,6 @@ * * @file pios_com.c * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) * @brief COM layer functions * @see The GNU Public License (GPL) Version 3 * @@ -161,7 +160,7 @@ out_fail: static void PIOS_COM_UnblockRx(struct pios_com_dev * com_dev, bool * need_yield) { #if defined(PIOS_INCLUDE_FREERTOS) - static signed portBASE_TYPE xHigherPriorityTaskWoken; + static signed portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; xSemaphoreGiveFromISR(com_dev->rx_sem, &xHigherPriorityTaskWoken); if (xHigherPriorityTaskWoken != pdFALSE) { @@ -177,7 +176,7 @@ static void PIOS_COM_UnblockRx(struct pios_com_dev * com_dev, bool * need_yield) static void PIOS_COM_UnblockTx(struct pios_com_dev * com_dev, bool * need_yield) { #if defined(PIOS_INCLUDE_FREERTOS) - static signed portBASE_TYPE xHigherPriorityTaskWoken; + static signed portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; xSemaphoreGiveFromISR(com_dev->tx_sem, &xHigherPriorityTaskWoken); if (xHigherPriorityTaskWoken != pdFALSE) { @@ -272,7 +271,7 @@ int32_t PIOS_COM_ChangeBaud(uint32_t com_id, uint32_t baud) * \return -1 if port not available * \return -2 if non-blocking mode activated: buffer is full * caller should retry until buffer is free again -* \return 0 on success +* \return number of bytes transmitted on success */ int32_t PIOS_COM_SendBufferNonBlocking(uint32_t com_id, const uint8_t *buffer, uint16_t len) { @@ -285,7 +284,7 @@ int32_t PIOS_COM_SendBufferNonBlocking(uint32_t com_id, const uint8_t *buffer, u PIOS_Assert(com_dev->has_tx); - if (len >= fifoBuf_getFree(&com_dev->tx)) { + if (len > fifoBuf_getFree(&com_dev->tx)) { /* Buffer cannot accept all requested bytes (retry) */ return -2; } @@ -302,7 +301,7 @@ int32_t PIOS_COM_SendBufferNonBlocking(uint32_t com_id, const uint8_t *buffer, u } } - return (0); + return (bytes_into_fifo); } /** @@ -312,7 +311,7 @@ int32_t PIOS_COM_SendBufferNonBlocking(uint32_t com_id, const uint8_t *buffer, u * \param[in] buffer character buffer * \param[in] len buffer length * \return -1 if port not available -* \return 0 on success +* \return number of bytes transmitted on success */ int32_t PIOS_COM_SendBuffer(uint32_t com_id, const uint8_t *buffer, uint16_t len) { @@ -325,25 +324,46 @@ int32_t PIOS_COM_SendBuffer(uint32_t com_id, const uint8_t *buffer, uint16_t len PIOS_Assert(com_dev->has_tx); - int32_t rc; - do { - rc = PIOS_COM_SendBufferNonBlocking(com_id, buffer, len); + uint32_t max_frag_len = fifoBuf_getSize(&com_dev->tx); + uint32_t bytes_to_send = len; + while (bytes_to_send) { + uint32_t frag_size; + if (bytes_to_send > max_frag_len) { + frag_size = max_frag_len; + } else { + frag_size = bytes_to_send; + } + int32_t rc = PIOS_COM_SendBufferNonBlocking(com_id, buffer, frag_size); + if (rc >= 0) { + bytes_to_send -= rc; + buffer += rc; + } else { + switch (rc) { + case -1: + /* Device is invalid, this will never work */ + return -1; + case -2: + /* Device is busy, wait for the underlying device to free some space and retry */ + /* Make sure the transmitter is running while we wait */ + if (com_dev->driver->tx_start) { + (com_dev->driver->tx_start)(com_dev->lower_id, + fifoBuf_getUsed(&com_dev->tx)); + } #if defined(PIOS_INCLUDE_FREERTOS) - if (rc == -2) { - /* Make sure the transmitter is running while we wait */ - if (com_dev->driver->tx_start) { - (com_dev->driver->tx_start)(com_dev->lower_id, - fifoBuf_getUsed(&com_dev->tx)); - } - if (xSemaphoreTake(com_dev->tx_sem, portMAX_DELAY) != pdTRUE) { - return -3; - } - } + if (xSemaphoreTake(com_dev->tx_sem, 5000) != pdTRUE) { + return -3; + } #endif - } while (rc == -2); + continue; + default: + /* Unhandled return code */ + return rc; + } + } + } - return rc; + return len; } /** @@ -463,7 +483,7 @@ uint16_t PIOS_COM_ReceiveBuffer(uint32_t com_id, uint8_t * buf, uint16_t buf_len uint16_t bytes_from_fifo = fifoBuf_getData(&com_dev->rx, buf, buf_len); PIOS_IRQ_Enable(); - if (bytes_from_fifo == 0 && timeout_ms > 0) { + if (bytes_from_fifo == 0) { /* No more bytes in receive buffer */ /* Make sure the receiver is running while we wait */ if (com_dev->driver->rx_start) { @@ -471,41 +491,25 @@ uint16_t PIOS_COM_ReceiveBuffer(uint32_t com_id, uint8_t * buf, uint16_t buf_len (com_dev->driver->rx_start)(com_dev->lower_id, fifoBuf_getFree(&com_dev->rx)); } + if (timeout_ms > 0) { #if defined(PIOS_INCLUDE_FREERTOS) - if (xSemaphoreTake(com_dev->rx_sem, timeout_ms / portTICK_RATE_MS) == pdTRUE) { - /* Make sure we don't come back here again */ - timeout_ms = 0; - goto check_again; - } + if (xSemaphoreTake(com_dev->rx_sem, timeout_ms / portTICK_RATE_MS) == pdTRUE) { + /* Make sure we don't come back here again */ + timeout_ms = 0; + goto check_again; + } #else - PIOS_DELAY_WaitmS(1); - timeout_ms--; - goto check_again; + PIOS_DELAY_WaitmS(1); + timeout_ms--; + goto check_again; #endif + } } /* Return received byte */ return (bytes_from_fifo); } -/** -* Get the number of bytes waiting in the buffer -* \param[in] port COM port -* \return Number of bytes used in buffer -*/ -int32_t PIOS_COM_ReceiveBufferUsed(uint32_t com_id) -{ - struct pios_com_dev * com_dev = (struct pios_com_dev *)com_id; - - if (!PIOS_COM_validate(com_dev)) { - /* Undefined COM port for this board (see pios_board.c) */ - PIOS_Assert(0); - } - - PIOS_Assert(com_dev->has_rx); - return (fifoBuf_getUsed(&com_dev->rx)); -} - #endif /** diff --git a/flight/PiOS/Common/pios_com_msg.c b/flight/PiOS/Common/pios_com_msg.c new file mode 100644 index 000000000..c1cebe1d9 --- /dev/null +++ b/flight/PiOS/Common/pios_com_msg.c @@ -0,0 +1,185 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_COM COM MSG layer functions + * @brief Hardware communication layer + * @{ + * + * @file pios_com_msg.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief COM MSG layer functions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_COM_MSG) + +#include "pios_com.h" + +#define PIOS_COM_MSG_MAX_LEN 63 + +struct pios_com_msg_dev { + uint32_t lower_id; + const struct pios_com_driver * driver; + + uint8_t rx_msg_buffer[PIOS_COM_MSG_MAX_LEN]; + volatile bool rx_msg_full; + + uint8_t tx_msg_buffer[PIOS_COM_MSG_MAX_LEN]; + volatile bool tx_msg_full; +}; + +static struct pios_com_msg_dev com_msg_dev; + +static uint16_t PIOS_COM_MSG_TxOutCallback(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, bool * need_yield); +static uint16_t PIOS_COM_MSG_RxInCallback(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, bool * need_yield); + +int32_t PIOS_COM_MSG_Init(uint32_t * com_id, const struct pios_com_driver * driver, uint32_t lower_id) +{ + PIOS_Assert(com_id); + PIOS_Assert(driver); + + PIOS_Assert(driver->bind_tx_cb); + PIOS_Assert(driver->bind_rx_cb); + + struct pios_com_msg_dev * com_dev = &com_msg_dev; + + com_dev->driver = driver; + com_dev->lower_id = lower_id; + + com_dev->rx_msg_full = false; + (com_dev->driver->bind_rx_cb)(lower_id, PIOS_COM_MSG_RxInCallback, (uint32_t)com_dev); + (com_dev->driver->rx_start)(com_dev->lower_id, sizeof(com_dev->rx_msg_buffer)); + + com_dev->tx_msg_full = false; + (com_dev->driver->bind_tx_cb)(lower_id, PIOS_COM_MSG_TxOutCallback, (uint32_t)com_dev); + + *com_id = (uint32_t)com_dev; + return(0); +} + +static uint16_t PIOS_COM_MSG_TxOutCallback(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, bool * need_yield) +{ + struct pios_com_msg_dev * com_dev = (struct pios_com_msg_dev *)context; + + PIOS_Assert(buf); + PIOS_Assert(buf_len); + + uint16_t bytes_from_fifo = 0; + + if (com_dev->tx_msg_full && (buf_len >= sizeof(com_dev->tx_msg_buffer))) { + /* Room for an entire message, send it */ + memcpy(buf, com_dev->tx_msg_buffer, sizeof(com_dev->tx_msg_buffer)); + bytes_from_fifo = sizeof(com_dev->tx_msg_buffer); + com_dev->tx_msg_full = false; + } + + if (headroom) { + if (com_dev->tx_msg_full) { + *headroom = sizeof(com_dev->tx_msg_buffer); + } else { + *headroom = 0; + } + } + + return (bytes_from_fifo); +} + +static uint16_t PIOS_COM_MSG_RxInCallback(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, bool * need_yield) +{ + struct pios_com_msg_dev * com_dev = (struct pios_com_msg_dev *)context; + + uint16_t bytes_into_fifo = 0; + + if (!com_dev->rx_msg_full && (buf_len >= sizeof(com_dev->rx_msg_buffer))) { + memcpy(com_dev->rx_msg_buffer, buf, sizeof(com_dev->rx_msg_buffer)); + bytes_into_fifo = sizeof(com_dev->rx_msg_buffer); + com_dev->rx_msg_full = true; + } + + if (headroom) { + if (!com_dev->rx_msg_full) { + *headroom = sizeof(com_dev->rx_msg_buffer); + } else { + *headroom = 0; + } + } + + return (bytes_into_fifo); +} + +int32_t PIOS_COM_MSG_Send(uint32_t com_id, const uint8_t *msg, uint16_t msg_len) +{ + PIOS_Assert(msg); + PIOS_Assert(msg_len); + + struct pios_com_msg_dev * com_dev = (struct pios_com_msg_dev *)com_id; + + PIOS_Assert(msg_len == sizeof(com_dev->tx_msg_buffer)); + + /* Wait forever for room in the tx buffer */ + while (com_dev->tx_msg_full) { + /* Kick the transmitter while we wait */ + if (com_dev->driver->tx_start) { + (com_dev->driver->tx_start)(com_dev->lower_id, sizeof(com_dev->tx_msg_buffer)); + } + } + + memcpy((void *) com_dev->tx_msg_buffer, msg, msg_len); + com_dev->tx_msg_full = true; + + /* Kick the transmitter now that we've queued our message */ + if (com_dev->driver->tx_start) { + (com_dev->driver->tx_start)(com_dev->lower_id, sizeof(com_dev->tx_msg_buffer)); + } + + return 0; +} + +uint16_t PIOS_COM_MSG_Receive(uint32_t com_id, uint8_t * msg, uint16_t msg_len) +{ + PIOS_Assert(msg); + PIOS_Assert(msg_len); + + struct pios_com_msg_dev * com_dev = (struct pios_com_msg_dev *)com_id; + + PIOS_Assert(msg_len == sizeof(com_dev->rx_msg_buffer)); + + if (!com_dev->rx_msg_full) { + /* There's room in our buffer, kick the receiver */ + (com_dev->driver->rx_start)(com_dev->lower_id, sizeof(com_dev->rx_msg_buffer)); + } else { + memcpy(msg, com_dev->rx_msg_buffer, msg_len); + com_dev->rx_msg_full = false; + + return msg_len; + } + + return 0; +} + +#endif /* PIOS_INCLUDE_COM_MSG */ + +/** + * @} + * @} + */ diff --git a/flight/PiOS/Common/pios_i2c_esc.c b/flight/PiOS/Common/pios_i2c_esc.c index fdb58eba0..d440bfa48 100644 --- a/flight/PiOS/Common/pios_i2c_esc.c +++ b/flight/PiOS/Common/pios_i2c_esc.c @@ -93,7 +93,7 @@ bool PIOS_I2C_ESC_SetSpeed(uint8_t speed[4]) } }; - return PIOS_I2C_Transfer(PIOS_I2C_MAIN_ADAPTER, txn_list, NELEMENTS(txn_list)); + return PIOS_I2C_Transfer(PIOS_I2C_ESC_ADAPTER, txn_list, NELEMENTS(txn_list)); } bool PIOS_SetMKSpeed(uint8_t motornum, uint8_t speed) { @@ -115,7 +115,7 @@ bool PIOS_SetMKSpeed(uint8_t motornum, uint8_t speed) { } }; - return PIOS_I2C_Transfer(PIOS_I2C_MAIN_ADAPTER, txn_list, NELEMENTS(txn_list)); + return PIOS_I2C_Transfer(PIOS_I2C_ESC_ADAPTER, txn_list, NELEMENTS(txn_list)); } bool PIOS_SetAstec4Address(uint8_t new_address) { @@ -134,7 +134,7 @@ bool PIOS_SetAstec4Address(uint8_t new_address) { } }; - return PIOS_I2C_Transfer(PIOS_I2C_MAIN_ADAPTER, txn_list, NELEMENTS(txn_list)); + return PIOS_I2C_Transfer(PIOS_I2C_ESC_ADAPTER, txn_list, NELEMENTS(txn_list)); } bool PIOS_SetAstec4Speed(uint8_t motornum, uint8_t speed) { @@ -161,7 +161,7 @@ bool PIOS_SetAstec4Speed(uint8_t motornum, uint8_t speed) { } }; - return PIOS_I2C_Transfer(PIOS_I2C_MAIN_ADAPTER, txn_list, NELEMENTS(txn_list)); + return PIOS_I2C_Transfer(PIOS_I2C_ESC_ADAPTER, txn_list, NELEMENTS(txn_list)); } #endif diff --git a/flight/PiOS/Common/pios_usb_desc_hid_cdc.c b/flight/PiOS/Common/pios_usb_desc_hid_cdc.c new file mode 100644 index 000000000..cd4e8a1da --- /dev/null +++ b/flight/PiOS/Common/pios_usb_desc_hid_cdc.c @@ -0,0 +1,256 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB_DESC USB Descriptor definitions + * @brief USB Descriptor definitions for HID and CDC + * @{ + * + * @file pios_usb_desc_hid_cdc.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief USB Descriptor definitions for HID and CDC + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "pios_usb_desc_hid_cdc_priv.h" /* exported API */ +#include "pios_usb_defs.h" /* struct usb_*, USB_* */ +#include "pios_usb_board_data.h" /* PIOS_USB_BOARD_* */ +#include "pios_usbhook.h" /* PIOS_USBHOOK_Register* */ + +static const struct usb_device_desc device_desc = { + .bLength = sizeof(struct usb_device_desc), + .bDescriptorType = USB_DESC_TYPE_DEVICE, + .bcdUSB = htousbs(0x0200), + .bDeviceClass = 0x02, + .bDeviceSubClass = 0x00, + .bDeviceProtocol = 0x00, + .bMaxPacketSize0 = 64, /* Must be 64 for high-speed devices */ + .idVendor = htousbs(USB_VENDOR_ID_OPENPILOT), + .idProduct = htousbs(PIOS_USB_BOARD_PRODUCT_ID), + .bcdDevice = htousbs(PIOS_USB_BOARD_DEVICE_VER), + .iManufacturer = USB_STRING_DESC_VENDOR, + .iProduct = USB_STRING_DESC_PRODUCT, + .iSerialNumber = USB_STRING_DESC_SERIAL, + .bNumConfigurations = 1, +}; + +static const uint8_t hid_report_desc[36] = { + HID_GLOBAL_ITEM_2 (HID_TAG_GLOBAL_USAGE_PAGE), + 0x9C, 0xFF, /* Usage Page 0xFF9C (Vendor Defined) */ + HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), + 0x01, /* Usage ID 0x0001 (0x01-0x1F uaually for top-level collections) */ + + HID_MAIN_ITEM_1 (HID_TAG_MAIN_COLLECTION), + 0x01, /* Application */ + + /* Device -> Host emulated serial channel */ + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_ID), + 0x01, /* OpenPilot emulated serial channel (Device -> Host) */ + HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), + 0x02, + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_LOGICAL_MIN), + 0x00, /* Values range from min = 0x00 */ + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_LOGICAL_MAX), + 0xFF, /* Values range to max = 0xFF */ + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_SIZE), + 0x08, /* 8 bits wide */ + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_CNT), + PIOS_USB_BOARD_HID_DATA_LENGTH-1, /* Need to leave room for a report ID */ + HID_MAIN_ITEM_1 (HID_TAG_MAIN_INPUT), + 0x03, /* Variable, Constant (read-only) */ + + /* Host -> Host emulated serial channel */ + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_ID), + 0x02, /* OpenPilot emulated Serial Channel (Host -> Device) */ + HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), + 0x02, + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_LOGICAL_MIN), + 0x00, /* Values range from min = 0x00 */ + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_LOGICAL_MAX), + 0xFF, /* Values range to max = 0xFF */ + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_SIZE), + 0x08, /* 8 bits wide */ + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_CNT), + PIOS_USB_BOARD_HID_DATA_LENGTH-1, /* Need to leave room for a report ID */ + HID_MAIN_ITEM_1 (HID_TAG_MAIN_OUTPUT), + 0x82, /* Volatile, Variable */ + + HID_MAIN_ITEM_0 (HID_TAG_MAIN_ENDCOLLECTION), +}; + +struct usb_config_hid_cdc { + struct usb_configuration_desc config; + struct usb_interface_association_desc iad; + struct usb_interface_desc hid_if; + struct usb_hid_desc hid; + struct usb_endpoint_desc hid_in; + struct usb_endpoint_desc hid_out; + struct usb_interface_desc cdc_control_if; + struct usb_cdc_header_func_desc cdc_header; + struct usb_cdc_callmgmt_func_desc cdc_callmgmt; + struct usb_cdc_acm_func_desc cdc_acm; + struct usb_cdc_union_func_desc cdc_union; + struct usb_endpoint_desc cdc_mgmt_in; + struct usb_interface_desc cdc_data_if; + struct usb_endpoint_desc cdc_in; + struct usb_endpoint_desc cdc_out; +} __attribute__((packed)); + +static const struct usb_config_hid_cdc config_hid_cdc = { + .config = { + .bLength = sizeof(struct usb_configuration_desc), + .bDescriptorType = USB_DESC_TYPE_CONFIGURATION, + .wTotalLength = htousbs(sizeof(struct usb_config_hid_cdc)), + .bNumInterfaces = 3, + .bConfigurationValue = 1, + .iConfiguration = 0, + .bmAttributes = 0xC0, + .bMaxPower = 250/2, /* in units of 2ma */ + }, + .iad = { + .bLength = sizeof(struct usb_interface_association_desc), + .bDescriptorType = USB_DESC_TYPE_IAD, + .bFirstInterface = 0, + .bInterfaceCount = 2, + .bFunctionClass = 2, /* Communication */ + .bFunctionSubClass = 2, /* Abstract Control Model */ + .bFunctionProtocol = 0, /* V.25ter, Common AT commands */ + .iInterface = 0, + }, + .hid_if = { + .bLength = sizeof(struct usb_interface_desc), + .bDescriptorType = USB_DESC_TYPE_INTERFACE, + .bInterfaceNumber = 0, + .bAlternateSetting = 0, + .bNumEndpoints = 2, + .bInterfaceClass = USB_INTERFACE_CLASS_HID, + .bInterfaceSubClass = 0, /* no boot */ + .nInterfaceProtocol = 0, /* none */ + .iInterface = 0, + }, + .hid = { + .bLength = sizeof(struct usb_hid_desc), + .bDescriptorType = USB_DESC_TYPE_HID, + .bcdHID = htousbs(0x0110), + .bCountryCode = 0, + .bNumDescriptors = 1, + .bClassDescriptorType = USB_DESC_TYPE_REPORT, + .wItemLength = htousbs(sizeof(hid_report_desc)), + }, + .hid_in = { + .bLength = sizeof(struct usb_endpoint_desc), + .bDescriptorType = USB_DESC_TYPE_ENDPOINT, + .bEndpointAddress = USB_EP_IN(1), + .bmAttributes = USB_EP_ATTR_TT_INTERRUPT, + .wMaxPacketSize = htousbs(PIOS_USB_BOARD_HID_DATA_LENGTH), + .bInterval = 4, /* ms */ + }, + .hid_out = { + .bLength = sizeof(struct usb_endpoint_desc), + .bDescriptorType = USB_DESC_TYPE_ENDPOINT, + .bEndpointAddress = USB_EP_OUT(1), + .bmAttributes = USB_EP_ATTR_TT_INTERRUPT, + .wMaxPacketSize = htousbs(PIOS_USB_BOARD_HID_DATA_LENGTH), + .bInterval = 4, /* ms */ + }, + .cdc_control_if = { + .bLength = sizeof(struct usb_interface_desc), + .bDescriptorType = USB_DESC_TYPE_INTERFACE, + .bInterfaceNumber = 1, + .bAlternateSetting = 0, + .bNumEndpoints = 1, + .bInterfaceClass = USB_INTERFACE_CLASS_CDC, + .bInterfaceSubClass = 2, /* Abstract Control Model */ + .nInterfaceProtocol = 1, /* V.25ter, Common AT commands */ + .iInterface = 0, + }, + .cdc_header = { + .bLength = sizeof(struct usb_cdc_header_func_desc), + .bDescriptorType = USB_DESC_TYPE_CLASS_SPECIFIC, + .bDescriptorSubType = USB_CDC_DESC_SUBTYPE_HEADER, + .bcdCDC = htousbs(0x0110), + }, + .cdc_callmgmt = { + .bLength = sizeof(struct usb_cdc_callmgmt_func_desc), + .bDescriptorType = USB_DESC_TYPE_CLASS_SPECIFIC, + .bDescriptorSubType = USB_CDC_DESC_SUBTYPE_CALLMGMT, + .bmCapabilities = 0x00, /* No call handling */ + .bDataInterface = 2, + }, + .cdc_acm = { + .bLength = sizeof(struct usb_cdc_acm_func_desc), + .bDescriptorType = USB_DESC_TYPE_CLASS_SPECIFIC, + .bDescriptorSubType = USB_CDC_DESC_SUBTYPE_ABSTRACT_CTRL, + .bmCapabilities = 0, + }, + .cdc_union = { + .bLength = sizeof(struct usb_cdc_union_func_desc), + .bDescriptorType = USB_DESC_TYPE_CLASS_SPECIFIC, + .bDescriptorSubType = USB_CDC_DESC_SUBTYPE_UNION, + .bMasterInterface = 1, + .bSlaveInterface = 2, + }, + .cdc_mgmt_in = { + .bLength = sizeof(struct usb_endpoint_desc), + .bDescriptorType = USB_DESC_TYPE_ENDPOINT, + .bEndpointAddress = USB_EP_IN(2), + .bmAttributes = USB_EP_ATTR_TT_INTERRUPT, + .wMaxPacketSize = htousbs(PIOS_USB_BOARD_CDC_MGMT_LENGTH), + .bInterval = 4, /* ms */ + }, + .cdc_data_if = { + .bLength = sizeof(struct usb_interface_desc), + .bDescriptorType = USB_DESC_TYPE_INTERFACE, + .bInterfaceNumber = 2, + .bAlternateSetting = 0, + .bNumEndpoints = 2, + .bInterfaceClass = USB_INTERFACE_CLASS_DATA, + .bInterfaceSubClass = 0, + .nInterfaceProtocol = 0, /* No class specific protocol */ + .iInterface = 0, + }, + .cdc_in = { + .bLength = sizeof(struct usb_endpoint_desc), + .bDescriptorType = USB_DESC_TYPE_ENDPOINT, + .bEndpointAddress = USB_EP_IN(3), + .bmAttributes = USB_EP_ATTR_TT_BULK, + .wMaxPacketSize = htousbs(PIOS_USB_BOARD_CDC_DATA_LENGTH), + .bInterval = 0, /* ms */ + }, + .cdc_out = { + .bLength = sizeof(struct usb_endpoint_desc), + .bDescriptorType = USB_DESC_TYPE_ENDPOINT, + .bEndpointAddress = USB_EP_OUT(3), + .bmAttributes = USB_EP_ATTR_TT_BULK, /* Bulk */ + .wMaxPacketSize = htousbs(PIOS_USB_BOARD_CDC_DATA_LENGTH), + .bInterval = 0, /* ms */ + }, +}; + +int32_t PIOS_USB_DESC_HID_CDC_Init(void) +{ + PIOS_USBHOOK_RegisterConfig(1, (uint8_t *)&config_hid_cdc, sizeof(config_hid_cdc)); + + PIOS_USBHOOK_RegisterDevice((uint8_t *)&device_desc, sizeof(device_desc)); + + PIOS_USBHOOK_RegisterHidInterface((uint8_t *)&(config_hid_cdc.hid_if), sizeof(config_hid_cdc.hid_if)); + PIOS_USBHOOK_RegisterHidReport((uint8_t *)hid_report_desc, sizeof(hid_report_desc)); + + return 0; +} diff --git a/flight/PiOS/Common/pios_usb_desc_hid_only.c b/flight/PiOS/Common/pios_usb_desc_hid_only.c new file mode 100644 index 000000000..168efe841 --- /dev/null +++ b/flight/PiOS/Common/pios_usb_desc_hid_only.c @@ -0,0 +1,164 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB_DESC USB Descriptor definitions + * @brief USB Descriptor definitions for HID only + * @{ + * + * @file pios_usb_desc_hid_only.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief USB Descriptor definitions for HID only + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "pios_usb_desc_hid_only_priv.h" /* exported API */ +#include "pios_usb_defs.h" /* struct usb_*, USB_* */ +#include "pios_usb_board_data.h" /* PIOS_USB_BOARD_* */ +#include "pios_usbhook.h" /* PIOS_USBHOOK_Register* */ + +static const struct usb_device_desc device_desc = { + .bLength = sizeof(struct usb_device_desc), + .bDescriptorType = USB_DESC_TYPE_DEVICE, + .bcdUSB = htousbs(0x0200), + .bDeviceClass = 0x00, + .bDeviceSubClass = 0x00, + .bDeviceProtocol = 0x00, + .bMaxPacketSize0 = 64, /* Must be 64 for high-speed devices */ + .idVendor = htousbs(USB_VENDOR_ID_OPENPILOT), + .idProduct = htousbs(PIOS_USB_BOARD_PRODUCT_ID), + .bcdDevice = htousbs(PIOS_USB_BOARD_DEVICE_VER), + .iManufacturer = 1, + .iProduct = 2, + .iSerialNumber = 3, + .bNumConfigurations = 1, +}; + +static const uint8_t hid_report_desc[36] = { + HID_GLOBAL_ITEM_2 (HID_TAG_GLOBAL_USAGE_PAGE), + 0x9C, 0xFF, /* Usage Page 0xFF9C (Vendor Defined) */ + HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), + 0x01, /* Usage ID 0x0001 (0x01-0x1F uaually for top-level collections) */ + + HID_MAIN_ITEM_1 (HID_TAG_MAIN_COLLECTION), + 0x01, /* Application */ + + /* Device -> Host emulated serial channel */ + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_ID), + 0x01, /* OpenPilot emulated serial channel (Device -> Host) */ + HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), + 0x02, + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_LOGICAL_MIN), + 0x00, /* Values range from min = 0x00 */ + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_LOGICAL_MAX), + 0xFF, /* Values range to max = 0xFF */ + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_SIZE), + 0x08, /* 8 bits wide */ + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_CNT), + PIOS_USB_BOARD_HID_DATA_LENGTH-1, /* Need to leave room for a report ID */ + HID_MAIN_ITEM_1 (HID_TAG_MAIN_INPUT), + 0x03, /* Variable, Constant (read-only) */ + + /* Host -> Host emulated serial channel */ + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_ID), + 0x02, /* OpenPilot emulated Serial Channel (Host -> Device) */ + HID_LOCAL_ITEM_1 (HID_TAG_LOCAL_USAGE), + 0x02, + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_LOGICAL_MIN), + 0x00, /* Values range from min = 0x00 */ + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_LOGICAL_MAX), + 0xFF, /* Values range to max = 0xFF */ + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_SIZE), + 0x08, /* 8 bits wide */ + HID_GLOBAL_ITEM_1 (HID_TAG_GLOBAL_REPORT_CNT), + PIOS_USB_BOARD_HID_DATA_LENGTH-1, /* Need to leave room for a report ID */ + HID_MAIN_ITEM_1 (HID_TAG_MAIN_OUTPUT), + 0x82, /* Volatile, Variable */ + + HID_MAIN_ITEM_0 (HID_TAG_MAIN_ENDCOLLECTION), +}; + +struct usb_config_hid_only { + struct usb_configuration_desc config; + struct usb_interface_desc hid_if; + struct usb_hid_desc hid; + struct usb_endpoint_desc hid_in; + struct usb_endpoint_desc hid_out; +} __attribute__((packed)); + +const struct usb_config_hid_only config_hid_only = { + .config = { + .bLength = sizeof(struct usb_configuration_desc), + .bDescriptorType = USB_DESC_TYPE_CONFIGURATION, + .wTotalLength = htousbs(sizeof(struct usb_config_hid_only)), + .bNumInterfaces = 1, + .bConfigurationValue = 1, + .iConfiguration = 0, + .bmAttributes = 0xC0, + .bMaxPower = 250/2, /* in units of 2ma */ + }, + .hid_if = { + .bLength = sizeof(struct usb_interface_desc), + .bDescriptorType = USB_DESC_TYPE_INTERFACE, + .bInterfaceNumber = 0, + .bAlternateSetting = 0, + .bNumEndpoints = 2, + .bInterfaceClass = USB_INTERFACE_CLASS_HID, + .bInterfaceSubClass = 0, /* no boot */ + .nInterfaceProtocol = 0, /* none */ + .iInterface = 0, + }, + .hid = { + .bLength = sizeof(struct usb_hid_desc), + .bDescriptorType = USB_DESC_TYPE_HID, + .bcdHID = htousbs(0x0110), + .bCountryCode = 0, + .bNumDescriptors = 1, + .bClassDescriptorType = USB_DESC_TYPE_REPORT, + .wItemLength = htousbs(sizeof(hid_report_desc)), + }, + .hid_in = { + .bLength = sizeof(struct usb_endpoint_desc), + .bDescriptorType = USB_DESC_TYPE_ENDPOINT, + .bEndpointAddress = USB_EP_IN(1), + .bmAttributes = USB_EP_ATTR_TT_INTERRUPT, + .wMaxPacketSize = htousbs(PIOS_USB_BOARD_HID_DATA_LENGTH), + .bInterval = 4, /* ms */ + }, + .hid_out = { + .bLength = sizeof(struct usb_endpoint_desc), + .bDescriptorType = USB_DESC_TYPE_ENDPOINT, + .bEndpointAddress = USB_EP_OUT(1), + .bmAttributes = USB_EP_ATTR_TT_INTERRUPT, + .wMaxPacketSize = htousbs(PIOS_USB_BOARD_HID_DATA_LENGTH), + .bInterval = 4, /* ms */ + }, +}; + +int32_t PIOS_USB_DESC_HID_ONLY_Init(void) +{ + PIOS_USBHOOK_RegisterConfig(1, (uint8_t *)&config_hid_only, sizeof(config_hid_only)); + + PIOS_USBHOOK_RegisterDevice((uint8_t *)&device_desc, sizeof(device_desc)); + + PIOS_USBHOOK_RegisterHidInterface((uint8_t *)&(config_hid_only.hid_if), sizeof(config_hid_only.hid_if)); + PIOS_USBHOOK_RegisterHidReport((uint8_t *)hid_report_desc, sizeof(hid_report_desc)); + + return 0; +} diff --git a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_core.h b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_core.h index c4bac0caf..7e606e44b 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_core.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_core.h @@ -35,7 +35,7 @@ typedef enum _CONTROL_STATE typedef struct OneDescriptor { - uint8_t *Descriptor; + const uint8_t *Descriptor; uint16_t Descriptor_Size; } ONE_DESCRIPTOR, *PONE_DESCRIPTOR; @@ -80,7 +80,8 @@ typedef struct _ENDPOINT_INFO uint16_t Usb_wLength; uint16_t Usb_wOffset; uint16_t PacketSize; - uint8_t *(*CopyData)(uint16_t Length); + const uint8_t *(*CopyDataIn)(uint16_t Length); + uint8_t *(*CopyDataOut)(uint16_t Length); }ENDPOINT_INFO; /*-*-*-*-*-*-*-*-*-*-*-* Definitions for device level -*-*-*-*-*-*-*-*-*-*-*-*/ @@ -169,9 +170,9 @@ typedef struct _DEVICE_PROP RESULT (*Class_Get_Interface_Setting)(uint8_t Interface, uint8_t AlternateSetting); - uint8_t* (*GetDeviceDescriptor)(uint16_t Length); - uint8_t* (*GetConfigDescriptor)(uint16_t Length); - uint8_t* (*GetStringDescriptor)(uint16_t Length); + const uint8_t* (*GetDeviceDescriptor)(uint16_t Length); + const uint8_t* (*GetConfigDescriptor)(uint16_t Length); + const uint8_t* (*GetStringDescriptor)(uint16_t Length); /* This field is not used in current library version. It is kept only for compatibility with previous versions */ @@ -221,21 +222,21 @@ uint8_t In0_Process(void); RESULT Standard_SetEndPointFeature(void); RESULT Standard_SetDeviceFeature(void); -uint8_t *Standard_GetConfiguration(uint16_t Length); +const uint8_t *Standard_GetConfiguration(uint16_t Length); RESULT Standard_SetConfiguration(void); -uint8_t *Standard_GetInterface(uint16_t Length); +const uint8_t *Standard_GetInterface(uint16_t Length); RESULT Standard_SetInterface(void); -uint8_t *Standard_GetDescriptorData(uint16_t Length, PONE_DESCRIPTOR pDesc); +const uint8_t *Standard_GetDescriptorData(uint16_t Length, ONE_DESCRIPTOR *pDesc); -uint8_t *Standard_GetStatus(uint16_t Length); +const uint8_t *Standard_GetStatus(uint16_t Length); RESULT Standard_ClearFeature(void); void SetDeviceAddress(uint8_t); void NOP_Process(void); -/*extern*/ DEVICE_PROP Device_Property; -/*extern*/ USER_STANDARD_REQUESTS User_Standard_Requests; -/*extern*/ DEVICE Device_Table; -/*extern*/ DEVICE_INFO Device_Info; +extern DEVICE_PROP Device_Property; +extern USER_STANDARD_REQUESTS User_Standard_Requests; +extern DEVICE Device_Table; +extern DEVICE_INFO Device_Info; /* cells saving status during interrupt servicing */ extern __IO uint16_t SaveRState; diff --git a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_mem.h b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_mem.h index 4d43fbe8c..f7f0ace12 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_mem.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/inc/usb_mem.h @@ -22,7 +22,7 @@ /* Exported constants --------------------------------------------------------*/ /* Exported macro ------------------------------------------------------------*/ /* Exported functions ------------------------------------------------------- */ -void UserToPMABufferCopy(uint8_t *pbUsrBuf, uint16_t wPMABufAddr, uint16_t wNBytes); +void UserToPMABufferCopy(const uint8_t *pbUsrBuf, uint16_t wPMABufAddr, uint16_t wNBytes); void PMAToUserBufferCopy(uint8_t *pbUsrBuf, uint16_t wPMABufAddr, uint16_t wNBytes); /* External variables --------------------------------------------------------*/ diff --git a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_core.c b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_core.c index 8cdd749f5..75ddaa42e 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_core.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_core.c @@ -58,7 +58,7 @@ static void Data_Setup0(void); * Return : Return 1 , if the request is invalid when "Length" is 0. * Return "Buffer" if the "Length" is not 0. *******************************************************************************/ -uint8_t *Standard_GetConfiguration(uint16_t Length) +const uint8_t *Standard_GetConfiguration(uint16_t Length) { if (Length == 0) { @@ -104,7 +104,7 @@ RESULT Standard_SetConfiguration(void) * Return : Return 0, if the request is invalid when "Length" is 0. * Return "Buffer" if the "Length" is not 0. *******************************************************************************/ -uint8_t *Standard_GetInterface(uint16_t Length) +const uint8_t *Standard_GetInterface(uint16_t Length) { if (Length == 0) { @@ -160,7 +160,7 @@ RESULT Standard_SetInterface(void) * Return : Return 0, if the request is at end of data block, * or is invalid when "Length" is 0. *******************************************************************************/ -uint8_t *Standard_GetStatus(uint16_t Length) +const uint8_t *Standard_GetStatus(uint16_t Length) { if (Length == 0) { @@ -415,7 +415,7 @@ RESULT Standard_SetDeviceFeature(void) * wOffset The buffer pointed by this address contains at least * Length bytes. *******************************************************************************/ -uint8_t *Standard_GetDescriptorData(uint16_t Length, ONE_DESCRIPTOR *pDesc) +const uint8_t *Standard_GetDescriptorData(uint16_t Length, PONE_DESCRIPTOR pDesc) { uint32_t wOffset; @@ -443,7 +443,7 @@ void DataStageOut(void) save_rLength = pEPinfo->Usb_rLength; - if (pEPinfo->CopyData && save_rLength) + if (pEPinfo->CopyDataOut && save_rLength) { uint8_t *Buffer; uint32_t Length; @@ -454,7 +454,7 @@ void DataStageOut(void) Length = save_rLength; } - Buffer = (*pEPinfo->CopyData)(Length); + Buffer = (*pEPinfo->CopyDataOut)(Length); pEPinfo->Usb_rLength -= Length; pEPinfo->Usb_rOffset += Length; @@ -503,7 +503,7 @@ void DataStageIn(void) uint32_t save_wLength = pEPinfo->Usb_wLength; uint32_t ControlState = pInformation->ControlState; - uint8_t *DataBuffer; + const uint8_t *DataBuffer; uint32_t Length; if ((save_wLength == 0) && (ControlState == LAST_IN_DATA)) @@ -540,7 +540,7 @@ void DataStageIn(void) Length = save_wLength; } - DataBuffer = (*pEPinfo->CopyData)(Length); + DataBuffer = (*pEPinfo->CopyDataIn)(Length); #ifdef STM32F10X_CL PCD_EP_Write (ENDP0, DataBuffer, Length); @@ -697,7 +697,7 @@ exit_NoData_Setup0: *******************************************************************************/ void Data_Setup0(void) { - uint8_t *(*CopyRoutine)(uint16_t); + const uint8_t *(*CopyRoutine)(uint16_t); RESULT Result; uint32_t Request_No = pInformation->USBbRequest; @@ -802,7 +802,7 @@ void Data_Setup0(void) if (CopyRoutine) { pInformation->Ctrl_Info.Usb_wOffset = wOffset; - pInformation->Ctrl_Info.CopyData = CopyRoutine; + pInformation->Ctrl_Info.CopyDataIn = CopyRoutine; /* sb in the original the cast to word was directly */ /* now the cast is made step by step */ (*CopyRoutine)(0); diff --git a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_mem.c b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_mem.c index e729b844c..ca50a23c4 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_mem.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32_USB-FS-Device_Driver/src/usb_mem.c @@ -33,7 +33,7 @@ * Output : None. * Return : None . *******************************************************************************/ -void UserToPMABufferCopy(uint8_t *pbUsrBuf, uint16_t wPMABufAddr, uint16_t wNBytes) +void UserToPMABufferCopy(const uint8_t *pbUsrBuf, uint16_t wPMABufAddr, uint16_t wNBytes) { uint32_t n = (wNBytes + 1) >> 1; /* n = (wNBytes + 1) / 2 */ uint32_t i, temp1, temp2; diff --git a/flight/PiOS/STM32F10x/pios_exti.c b/flight/PiOS/STM32F10x/pios_exti.c index 5f5b058bd..6d4fb4882 100644 --- a/flight/PiOS/STM32F10x/pios_exti.c +++ b/flight/PiOS/STM32F10x/pios_exti.c @@ -44,7 +44,7 @@ void EXTI15_10_IRQHandler(void) portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; #endif /* PIOS_INCLUDE_FREERTOS */ -#if defined(PIOS_INCLUDE_BMP085) +#if defined(PIOS_INCLUDE_BMP085) && defined(PIOS_BMP085_HAS_GPIOS) if (EXTI_GetITStatus(PIOS_BMP085_EOC_EXTI_LINE) != RESET) { /* Read the ADC Value */ #if defined(PIOS_INCLUDE_FREERTOS) diff --git a/flight/PiOS/STM32F10x/pios_i2c.c b/flight/PiOS/STM32F10x/pios_i2c.c index 7cc50b307..d7252916c 100644 --- a/flight/PiOS/STM32F10x/pios_i2c.c +++ b/flight/PiOS/STM32F10x/pios_i2c.c @@ -8,7 +8,6 @@ * * @file pios_i2c.c * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) * @brief I2C Enable/Disable routines * @see The GNU Public License (GPL) Version 3 * @@ -892,6 +891,10 @@ int32_t PIOS_I2C_Init(uint32_t * i2c_id, const struct pios_i2c_adapter_cfg * cfg break; } + if (i2c_adapter->cfg->remap) { + GPIO_PinRemapConfig(i2c_adapter->cfg->remap, ENABLE); + } + /* Initialize the state machine */ i2c_adapter_fsm_init(i2c_adapter); diff --git a/flight/PiOS/STM32F10x/pios_spi.c b/flight/PiOS/STM32F10x/pios_spi.c index 6f9b62227..5303e7f0c 100644 --- a/flight/PiOS/STM32F10x/pios_spi.c +++ b/flight/PiOS/STM32F10x/pios_spi.c @@ -8,7 +8,6 @@ * * @file pios_spi.c * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) * @brief Hardware Abstraction Layer for SPI ports of STM32 * @see The GNU Public License (GPL) Version 3 * @notes diff --git a/flight/PiOS/STM32F10x/pios_usart.c b/flight/PiOS/STM32F10x/pios_usart.c index 68a9265ee..041738f70 100644 --- a/flight/PiOS/STM32F10x/pios_usart.c +++ b/flight/PiOS/STM32F10x/pios_usart.c @@ -8,7 +8,6 @@ * * @file pios_usart.c * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) * @brief USART commands. Inits USARTs, controls USARTs & Interupt handlers. (STM32 dependent) * @see The GNU Public License (GPL) Version 3 * @@ -63,6 +62,8 @@ struct pios_usart_dev { uint32_t rx_in_context; pios_com_callback tx_out_cb; uint32_t tx_out_context; + + uint32_t rx_dropped; }; static bool PIOS_USART_validate(struct pios_usart_dev * usart_dev) @@ -285,7 +286,12 @@ static void PIOS_USART_generic_irq_handler(uint32_t usart_id) if (sr & USART_SR_RXNE) { uint8_t byte = dr; if (usart_dev->rx_in_cb) { - (void) (usart_dev->rx_in_cb)(usart_dev->rx_in_context, &byte, 1, NULL, &rx_need_yield); + uint16_t rc; + rc = (usart_dev->rx_in_cb)(usart_dev->rx_in_context, &byte, 1, NULL, &rx_need_yield); + if (rc < 1) { + /* Lost bytes on rx */ + usart_dev->rx_dropped += 1; + } } } diff --git a/flight/PiOS/STM32F10x/pios_usb.c b/flight/PiOS/STM32F10x/pios_usb.c new file mode 100644 index 000000000..15decfca1 --- /dev/null +++ b/flight/PiOS/STM32F10x/pios_usb.c @@ -0,0 +1,218 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB USB Setup Functions + * @brief PIOS USB device implementation + * @{ + * + * @file pios_usb.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief USB device functions (STM32 dependent code) + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Project Includes */ +#include "pios.h" +#include "usb_lib.h" +#include "pios_usb_board_data.h" +#include "stm32f10x.h" + +#include "pios_usb.h" +#include "pios_usb_priv.h" + +#if defined(PIOS_INCLUDE_USB_HID) + +/* Rx/Tx status */ +static uint8_t transfer_possible = 0; + +enum pios_usb_dev_magic { + PIOS_USB_DEV_MAGIC = 0x17365904, +}; + +struct pios_usb_dev { + enum pios_usb_dev_magic magic; + const struct pios_usb_cfg * cfg; +}; + +#if 0 +static bool PIOS_USB_validate(struct pios_usb_dev * usb_dev) +{ + return (usb_dev->magic == PIOS_USB_DEV_MAGIC); +} +#endif + +#if defined(PIOS_INCLUDE_FREERTOS) +static struct pios_usb_dev * PIOS_USB_alloc(void) +{ + struct pios_usb_dev * usb_dev; + + usb_dev = (struct pios_usb_dev *)pvPortMalloc(sizeof(*usb_dev)); + if (!usb_dev) return(NULL); + + usb_dev->magic = PIOS_USB_DEV_MAGIC; + return(usb_dev); +} +#else +static struct pios_usb_dev pios_usb_devs[PIOS_USB_MAX_DEVS]; +static uint8_t pios_usb_num_devs; +static struct pios_usb_dev * PIOS_USB_alloc(void) +{ + struct pios_usb_dev * usb_dev; + + if (pios_usb_num_devs >= PIOS_USB_MAX_DEVS) { + return (NULL); + } + + usb_dev = &pios_usb_devs[pios_usb_num_devs++]; + usb_dev->magic = PIOS_USB_DEV_MAGIC; + + return (usb_dev); +} +#endif + + +/** + * Initialises USB COM layer + * \return < 0 if initialisation failed + * \note Applications shouldn't call this function directly, instead please use \ref PIOS_COM layer functions + */ +static uint32_t pios_usb_com_id; +int32_t PIOS_USB_Init(uint32_t * usb_id, const struct pios_usb_cfg * cfg) +{ + PIOS_Assert(usb_id); + PIOS_Assert(cfg); + + struct pios_usb_dev * usb_dev; + + usb_dev = (struct pios_usb_dev *) PIOS_USB_alloc(); + if (!usb_dev) goto out_fail; + + /* Bind the configuration to the device instance */ + usb_dev->cfg = cfg; + + PIOS_USB_Reenumerate(); + + /* + * This is a horrible hack to make this available to + * the interrupt callbacks. This should go away ASAP. + */ + pios_usb_com_id = (uint32_t) usb_dev; + + /* Enable the USB Interrupts */ + NVIC_Init(&usb_dev->cfg->irq.init); + + /* Select USBCLK source */ + RCC_USBCLKConfig(RCC_USBCLKSource_PLLCLK_1Div5); + /* Enable the USB clock */ + RCC_APB1PeriphClockCmd(RCC_APB1Periph_USB, ENABLE); + + USB_Init(); + USB_SIL_Init(); + + *usb_id = (uint32_t) usb_dev; + + return 0; /* No error */ + +out_fail: + return(-1); +} + +/** + * This function is called by the USB driver on cable connection/disconnection + * \param[in] connected connection status (1 if connected) + * \return < 0 on errors + * \note Applications shouldn't call this function directly, instead please use \ref PIOS_COM layer functions + */ +int32_t PIOS_USB_ChangeConnectionState(uint32_t Connected) +{ + // In all cases: re-initialise USB HID driver + if (Connected) { + transfer_possible = 1; + + //TODO: Check SetEPRxValid(ENDP1); + +#if defined(USB_LED_ON) + USB_LED_ON; // turn the USB led on +#endif + } else { + // Cable disconnected: disable transfers + transfer_possible = 0; + +#if defined(USB_LED_OFF) + USB_LED_OFF; // turn the USB led off +#endif + } + + return 0; +} + +int32_t PIOS_USB_Reenumerate() +{ + /* Force USB reset and power-down (this will also release the USB pins for direct GPIO control) */ + _SetCNTR(CNTR_FRES | CNTR_PDWN); + + /* Using a "dirty" method to force a re-enumeration: */ + /* Force DPM (Pin PA12) low for ca. 10 mS before USB Tranceiver will be enabled */ + /* This overrules the external Pull-Up at PA12, and at least Windows & MacOS will enumerate again */ + GPIO_InitTypeDef GPIO_InitStructure; + GPIO_StructInit(&GPIO_InitStructure); + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; + GPIO_Init(GPIOA, &GPIO_InitStructure); + + PIOS_DELAY_WaitmS(50); + + /* Release power-down, still hold reset */ + _SetCNTR(CNTR_PDWN); + PIOS_DELAY_WaituS(5); + + /* CNTR_FRES = 0 */ + _SetCNTR(0); + + /* Clear pending interrupts */ + _SetISTR(0); + + /* Configure USB clock */ + /* USBCLK = PLLCLK / 1.5 */ + RCC_USBCLKConfig(RCC_USBCLKSource_PLLCLK_1Div5); + /* Enable USB clock */ + RCC_APB1PeriphClockCmd(RCC_APB1Periph_USB, ENABLE); + + return 0; +} + +/** + * This function returns the connection status of the USB HID interface + * \return 1: interface available + * \return 0: interface not available + * \note Applications shouldn't call this function directly, instead please use \ref PIOS_COM layer functions + */ +bool PIOS_USB_CheckAvailable(uint8_t id) +{ + return (PIOS_USB_DETECT_GPIO_PORT->IDR & PIOS_USB_DETECT_GPIO_PIN) != 0 && transfer_possible ? 1 : 0; +} + +#endif + +/** + * @} + * @} + */ diff --git a/flight/PiOS/STM32F10x/pios_usb_cdc.c b/flight/PiOS/STM32F10x/pios_usb_cdc.c new file mode 100644 index 000000000..4bb1303d9 --- /dev/null +++ b/flight/PiOS/STM32F10x/pios_usb_cdc.c @@ -0,0 +1,400 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB_COM USB COM Functions + * @brief PIOS USB COM implementation for CDC interfaces + * @notes This implements a CDC Serial Port + * @{ + * + * @file pios_usb_com_cdc.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief USB COM functions (STM32 dependent code) + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_USB_CDC) + +#include "pios_usb.h" +#include "pios_usb_cdc_priv.h" +#include "pios_usb_board_data.h" /* PIOS_BOARD_*_DATA_LENGTH */ + +static void PIOS_USB_CDC_RegisterTxCallback(uint32_t usbcdc_id, pios_com_callback tx_out_cb, uint32_t context); +static void PIOS_USB_CDC_RegisterRxCallback(uint32_t usbcdc_id, pios_com_callback rx_in_cb, uint32_t context); +static void PIOS_USB_CDC_TxStart(uint32_t usbcdc_id, uint16_t tx_bytes_avail); +static void PIOS_USB_CDC_RxStart(uint32_t usbcdc_id, uint16_t rx_bytes_avail); + +const struct pios_com_driver pios_usb_cdc_com_driver = { + .tx_start = PIOS_USB_CDC_TxStart, + .rx_start = PIOS_USB_CDC_RxStart, + .bind_tx_cb = PIOS_USB_CDC_RegisterTxCallback, + .bind_rx_cb = PIOS_USB_CDC_RegisterRxCallback, +}; + +enum pios_usb_cdc_dev_magic { + PIOS_USB_CDC_DEV_MAGIC = 0xAABBCCDD, +}; + +struct pios_usb_cdc_dev { + enum pios_usb_cdc_dev_magic magic; + const struct pios_usb_cdc_cfg * cfg; + + uint32_t lower_id; + + pios_com_callback rx_in_cb; + uint32_t rx_in_context; + pios_com_callback tx_out_cb; + uint32_t tx_out_context; + + uint8_t rx_packet_buffer[PIOS_USB_BOARD_CDC_DATA_LENGTH]; + uint8_t tx_packet_buffer[PIOS_USB_BOARD_CDC_DATA_LENGTH]; + + uint32_t rx_dropped; + uint32_t rx_oversize; +}; + +static bool PIOS_USB_CDC_validate(struct pios_usb_cdc_dev * usb_cdc_dev) +{ + return (usb_cdc_dev->magic == PIOS_USB_CDC_DEV_MAGIC); +} + +#if defined(PIOS_INCLUDE_FREERTOS) +static struct pios_usb_cdc_dev * PIOS_USB_CDC_alloc(void) +{ + struct pios_usb_cdc_dev * usb_cdc_dev; + + usb_cdc_dev = (struct pios_usb_cdc_dev *)pvPortMalloc(sizeof(*usb_cdc_dev)); + if (!usb_cdc_dev) return(NULL); + + usb_cdc_dev->magic = PIOS_USB_CDC_DEV_MAGIC; + return(usb_cdc_dev); +} +#else +static struct pios_usb_cdc_dev pios_usb_cdc_devs[PIOS_USB_CDC_MAX_DEVS]; +static uint8_t pios_usb_cdc_num_devs; +static struct pios_usb_cdc_dev * PIOS_USB_CDC_alloc(void) +{ + struct pios_usb_cdc_dev * usb_cdc_dev; + + if (pios_usb_cdc_num_devs >= PIOS_USB_CDC_MAX_DEVS) { + return (NULL); + } + + usb_cdc_dev = &pios_usb_cdc_devs[pios_usb_cdc_num_devs++]; + usb_cdc_dev->magic = PIOS_USB_CDC_DEV_MAGIC; + + return (usb_cdc_dev); +} +#endif + +static void PIOS_USB_CDC_DATA_EP_IN_Callback(void); +static void PIOS_USB_CDC_DATA_EP_OUT_Callback(void); +static void PIOS_USB_CDC_CTRL_EP_IN_Callback(void); + +static uint32_t pios_usb_cdc_id; + +/* Need a better way to pull these in */ +extern void (*pEpInt_IN[7])(void); +extern void (*pEpInt_OUT[7])(void); + +int32_t PIOS_USB_CDC_Init(uint32_t * usbcdc_id, const struct pios_usb_cdc_cfg * cfg, uint32_t lower_id) +{ + PIOS_Assert(usbcdc_id); + PIOS_Assert(cfg); + + struct pios_usb_cdc_dev * usb_cdc_dev; + + usb_cdc_dev = (struct pios_usb_cdc_dev *) PIOS_USB_CDC_alloc(); + if (!usb_cdc_dev) goto out_fail; + + /* Bind the configuration to the device instance */ + usb_cdc_dev->cfg = cfg; + usb_cdc_dev->lower_id = lower_id; + + pios_usb_cdc_id = (uint32_t) usb_cdc_dev; + + /* Bind lower level callbacks into the USB infrastructure */ + pEpInt_OUT[cfg->ctrl_tx_ep - 1] = PIOS_USB_CDC_CTRL_EP_IN_Callback; + pEpInt_IN[cfg->data_tx_ep - 1] = PIOS_USB_CDC_DATA_EP_IN_Callback; + pEpInt_OUT[cfg->data_rx_ep - 1] = PIOS_USB_CDC_DATA_EP_OUT_Callback; + + *usbcdc_id = (uint32_t) usb_cdc_dev; + + return 0; + +out_fail: + return -1; +} + + + +static void PIOS_USB_CDC_RegisterRxCallback(uint32_t usbcdc_id, pios_com_callback rx_in_cb, uint32_t context) +{ + struct pios_usb_cdc_dev * usb_cdc_dev = (struct pios_usb_cdc_dev *)usbcdc_id; + + bool valid = PIOS_USB_CDC_validate(usb_cdc_dev); + PIOS_Assert(valid); + + /* + * Order is important in these assignments since ISR uses _cb + * field to determine if it's ok to dereference _cb and _context + */ + usb_cdc_dev->rx_in_context = context; + usb_cdc_dev->rx_in_cb = rx_in_cb; +} + +static void PIOS_USB_CDC_RegisterTxCallback(uint32_t usbcdc_id, pios_com_callback tx_out_cb, uint32_t context) +{ + struct pios_usb_cdc_dev * usb_cdc_dev = (struct pios_usb_cdc_dev *)usbcdc_id; + + bool valid = PIOS_USB_CDC_validate(usb_cdc_dev); + PIOS_Assert(valid); + + /* + * Order is important in these assignments since ISR uses _cb + * field to determine if it's ok to dereference _cb and _context + */ + usb_cdc_dev->tx_out_context = context; + usb_cdc_dev->tx_out_cb = tx_out_cb; +} + +static void PIOS_USB_CDC_RxStart(uint32_t usbcdc_id, uint16_t rx_bytes_avail) { + struct pios_usb_cdc_dev * usb_cdc_dev = (struct pios_usb_cdc_dev *)usbcdc_id; + + bool valid = PIOS_USB_CDC_validate(usb_cdc_dev); + PIOS_Assert(valid); + + if (!PIOS_USB_CheckAvailable(usb_cdc_dev->lower_id)) { + return; + } + + // If endpoint was stalled and there is now space make it valid + PIOS_IRQ_Disable(); + if ((GetEPRxStatus(usb_cdc_dev->cfg->data_rx_ep) != EP_RX_VALID) && + (rx_bytes_avail >= sizeof(usb_cdc_dev->rx_packet_buffer))) { + SetEPRxStatus(usb_cdc_dev->cfg->data_rx_ep, EP_RX_VALID); + } + PIOS_IRQ_Enable(); +} + +static void PIOS_USB_CDC_SendData(struct pios_usb_cdc_dev * usb_cdc_dev) +{ + uint16_t bytes_to_tx; + + if (!usb_cdc_dev->tx_out_cb) { + return; + } + + bool need_yield = false; + bytes_to_tx = (usb_cdc_dev->tx_out_cb)(usb_cdc_dev->tx_out_context, + usb_cdc_dev->tx_packet_buffer, + sizeof(usb_cdc_dev->tx_packet_buffer), + NULL, + &need_yield); + if (bytes_to_tx == 0) { + return; + } + + UserToPMABufferCopy(usb_cdc_dev->tx_packet_buffer, + GetEPTxAddr(usb_cdc_dev->cfg->data_tx_ep), + bytes_to_tx); + SetEPTxCount(usb_cdc_dev->cfg->data_tx_ep, bytes_to_tx); + SetEPTxValid(usb_cdc_dev->cfg->data_tx_ep); + +#if defined(PIOS_INCLUDE_FREERTOS) + if (need_yield) { + vPortYieldFromISR(); + } +#endif /* PIOS_INCLUDE_FREERTOS */ +} + +static void PIOS_USB_CDC_TxStart(uint32_t usbcdc_id, uint16_t tx_bytes_avail) +{ + struct pios_usb_cdc_dev * usb_cdc_dev = (struct pios_usb_cdc_dev *)usbcdc_id; + + bool valid = PIOS_USB_CDC_validate(usb_cdc_dev); + PIOS_Assert(valid); + + if (!PIOS_USB_CheckAvailable(usb_cdc_dev->lower_id)) { + return; + } + + if (GetEPTxStatus(usb_cdc_dev->cfg->data_tx_ep) == EP_TX_VALID) { + /* Endpoint is already transmitting */ + return; + } + + PIOS_USB_CDC_SendData(usb_cdc_dev); +} + +static void PIOS_USB_CDC_DATA_EP_IN_Callback(void) +{ + struct pios_usb_cdc_dev * usb_cdc_dev = (struct pios_usb_cdc_dev *)pios_usb_cdc_id; + + bool valid = PIOS_USB_CDC_validate(usb_cdc_dev); + PIOS_Assert(valid); + + PIOS_USB_CDC_SendData(usb_cdc_dev); +} + +static void PIOS_USB_CDC_DATA_EP_OUT_Callback(void) +{ + struct pios_usb_cdc_dev * usb_cdc_dev = (struct pios_usb_cdc_dev *)pios_usb_cdc_id; + + bool valid = PIOS_USB_CDC_validate(usb_cdc_dev); + PIOS_Assert(valid); + + uint32_t DataLength; + + /* Get the number of received data on the selected Endpoint */ + DataLength = GetEPRxCount(usb_cdc_dev->cfg->data_rx_ep); + if (DataLength > sizeof(usb_cdc_dev->rx_packet_buffer)) { + usb_cdc_dev->rx_oversize++; + DataLength = sizeof(usb_cdc_dev->rx_packet_buffer); + } + + /* Use the memory interface function to read from the selected endpoint */ + PMAToUserBufferCopy((uint8_t *) usb_cdc_dev->rx_packet_buffer, + GetEPRxAddr(usb_cdc_dev->cfg->data_rx_ep), + DataLength); + + if (!usb_cdc_dev->rx_in_cb) { + /* No Rx call back registered, disable the receiver */ + SetEPRxStatus(usb_cdc_dev->cfg->data_rx_ep, EP_RX_NAK); + return; + } + + uint16_t headroom; + bool need_yield = false; + uint16_t rc; + rc = (usb_cdc_dev->rx_in_cb)(usb_cdc_dev->rx_in_context, + usb_cdc_dev->rx_packet_buffer, + DataLength, + &headroom, + &need_yield); + + if (rc < DataLength) { + /* Lost bytes on rx */ + usb_cdc_dev->rx_dropped += (DataLength - rc); + } + + if (headroom >= sizeof(usb_cdc_dev->rx_packet_buffer)) { + /* We have room for a maximum length message */ + SetEPRxStatus(usb_cdc_dev->cfg->data_rx_ep, EP_RX_VALID); + } else { + /* Not enough room left for a message, apply backpressure */ + SetEPRxStatus(usb_cdc_dev->cfg->data_rx_ep, EP_RX_NAK); + } + +#if defined(PIOS_INCLUDE_FREERTOS) + if (need_yield) { + vPortYieldFromISR(); + } +#endif /* PIOS_INCLUDE_FREERTOS */ +} + +RESULT PIOS_USB_CDC_SetControlLineState(void) +{ + struct pios_usb_cdc_dev * usb_cdc_dev = (struct pios_usb_cdc_dev *)pios_usb_cdc_id; + + bool valid = PIOS_USB_CDC_validate(usb_cdc_dev); + PIOS_Assert(valid); + + static uint16_t control_line_state; + + uint8_t wValue0 = pInformation->USBwValue0; + uint8_t wValue1 = pInformation->USBwValue1; + + control_line_state = wValue1 << 8 | wValue0; + + return USB_SUCCESS; +} + +static struct usb_cdc_line_coding line_coding = { + .dwDTERate = htousbl(57600), + .bCharFormat = USB_CDC_LINE_CODING_STOP_1, + .bParityType = USB_CDC_LINE_CODING_PARITY_NONE, + .bDataBits = 8, +}; + +RESULT PIOS_USB_CDC_SetLineCoding(void) +{ + struct pios_usb_cdc_dev * usb_cdc_dev = (struct pios_usb_cdc_dev *)pios_usb_cdc_id; + + bool valid = PIOS_USB_CDC_validate(usb_cdc_dev); + PIOS_Assert(valid); + + return USB_SUCCESS; +} + +const uint8_t *PIOS_USB_CDC_GetLineCoding(uint16_t Length) +{ + struct pios_usb_cdc_dev * usb_cdc_dev = (struct pios_usb_cdc_dev *)pios_usb_cdc_id; + + bool valid = PIOS_USB_CDC_validate(usb_cdc_dev); + PIOS_Assert(valid); + + if (Length == 0) { + pInformation->Ctrl_Info.Usb_wLength = sizeof(line_coding); + return NULL; + } else { + return ((uint8_t *) &line_coding); + } +} + +struct usb_cdc_serial_state_report uart_state = { + .bmRequestType = 0xA1, + .bNotification = USB_CDC_NOTIFICATION_SERIAL_STATE, + .wValue = 0, + .wIndex = htousbs(1), + .wLength = htousbs(2), + .bmUartState = htousbs(0), +}; + +static void PIOS_USB_CDC_CTRL_EP_IN_Callback(void) +{ + struct pios_usb_cdc_dev * usb_cdc_dev = (struct pios_usb_cdc_dev *)pios_usb_cdc_id; + + bool valid = PIOS_USB_CDC_validate(usb_cdc_dev); + PIOS_Assert(valid); + + /* Give back UART State Bitmap */ + /* UART State Bitmap + * 15-7: reserved + * 6: bOverRun overrun error + * 5: bParity parity error + * 4: bFraming framing error + * 3: bRingSignal RI + * 2: bBreak break reception + * 1: bTxCarrier DSR + * 0: bRxCarrier DCD + */ + uart_state.bmUartState = htousbs(0x0003); + + UserToPMABufferCopy((uint8_t *) &uart_state, + GetEPTxAddr(usb_cdc_dev->cfg->data_tx_ep), + sizeof(uart_state)); + SetEPTxCount(usb_cdc_dev->cfg->data_tx_ep, PIOS_USB_BOARD_CDC_MGMT_LENGTH); + SetEPTxValid(usb_cdc_dev->cfg->data_tx_ep); +} + +#endif /* PIOS_INCLUDE_USB_CDC */ diff --git a/flight/PiOS/STM32F10x/pios_usb_hid.c b/flight/PiOS/STM32F10x/pios_usb_hid.c index 8644dd517..e70c93046 100644 --- a/flight/PiOS/STM32F10x/pios_usb_hid.c +++ b/flight/PiOS/STM32F10x/pios_usb_hid.c @@ -2,16 +2,14 @@ ****************************************************************************** * @addtogroup PIOS PIOS Core hardware abstraction layer * @{ - * @addtogroup PIOS_USB_HID USB HID Functions - * @brief PIOS USB HID implementation - * @notes This implements a very simple HID device with a simple data in - * and data out endpoints. + * @addtogroup PIOS_USB_HID USB COM Functions + * @brief PIOS USB COM implementation for HID interfaces + * @notes This implements serial emulation over HID reports * @{ * * @file pios_usb_hid.c * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) - * @brief USB HID functions (STM32 dependent code) + * @brief USB COM functions (STM32 dependent code) * @see The GNU Public License (GPL) Version 3 * *****************************************************************************/ @@ -33,20 +31,19 @@ /* Project Includes */ #include "pios.h" -#include "usb_lib.h" -#include "pios_usb_hid_desc.h" -#include "stm32f10x.h" - -#include "pios_usb_hid_priv.h" #if defined(PIOS_INCLUDE_USB_HID) -static void PIOS_USB_HID_TxStart(uint32_t usbcom_id, uint16_t tx_bytes_avail); -static void PIOS_USB_HID_RxStart(uint32_t usbcom_id, uint16_t rx_bytes_avail); -static void PIOS_USB_HID_RegisterTxCallback(uint32_t usbcom_id, pios_com_callback tx_out_cb, uint32_t context); -static void PIOS_USB_HID_RegisterRxCallback(uint32_t usbcom_id, pios_com_callback rx_in_cb, uint32_t context); +#include "pios_usb.h" +#include "pios_usb_hid_priv.h" +#include "pios_usb_board_data.h" /* PIOS_BOARD_*_DATA_LENGTH */ -const struct pios_com_driver pios_usb_com_driver = { +static void PIOS_USB_HID_RegisterTxCallback(uint32_t usbhid_id, pios_com_callback tx_out_cb, uint32_t context); +static void PIOS_USB_HID_RegisterRxCallback(uint32_t usbhid_id, pios_com_callback rx_in_cb, uint32_t context); +static void PIOS_USB_HID_TxStart(uint32_t usbhid_id, uint16_t tx_bytes_avail); +static void PIOS_USB_HID_RxStart(uint32_t usbhid_id, uint16_t rx_bytes_avail); + +const struct pios_com_driver pios_usb_hid_com_driver = { .tx_start = PIOS_USB_HID_TxStart, .rx_start = PIOS_USB_HID_RxStart, .bind_tx_cb = PIOS_USB_HID_RegisterTxCallback, @@ -54,20 +51,25 @@ const struct pios_com_driver pios_usb_com_driver = { }; enum pios_usb_hid_dev_magic { - PIOS_USB_HID_DEV_MAGIC = 0xAABBCCDD, + PIOS_USB_HID_DEV_MAGIC = 0xAA00BB00, }; struct pios_usb_hid_dev { enum pios_usb_hid_dev_magic magic; const struct pios_usb_hid_cfg * cfg; + uint32_t lower_id; + pios_com_callback rx_in_cb; uint32_t rx_in_context; pios_com_callback tx_out_cb; uint32_t tx_out_context; - uint8_t rx_packet_buffer[PIOS_USB_HID_DATA_LENGTH + 2]; - uint8_t tx_packet_buffer[PIOS_USB_HID_DATA_LENGTH + 2]; + uint8_t rx_packet_buffer[PIOS_USB_BOARD_HID_DATA_LENGTH]; + uint8_t tx_packet_buffer[PIOS_USB_BOARD_HID_DATA_LENGTH]; + + uint32_t rx_dropped; + uint32_t rx_oversize; }; static bool PIOS_USB_HID_validate(struct pios_usb_hid_dev * usb_hid_dev) @@ -104,18 +106,18 @@ static struct pios_usb_hid_dev * PIOS_USB_HID_alloc(void) } #endif -/* Rx/Tx status */ -static uint8_t transfer_possible = 0; +static void PIOS_USB_HID_EP_IN_Callback(void); +static void PIOS_USB_HID_EP_OUT_Callback(void); -/** - * Initialises USB COM layer - * \return < 0 if initialisation failed - * \note Applications shouldn't call this function directly, instead please use \ref PIOS_COM layer functions - */ static uint32_t pios_usb_hid_id; -int32_t PIOS_USB_HID_Init(uint32_t * usb_hid_id, const struct pios_usb_hid_cfg * cfg) + +/* Need a better way to pull these in */ +extern void (*pEpInt_IN[7])(void); +extern void (*pEpInt_OUT[7])(void); + +int32_t PIOS_USB_HID_Init(uint32_t * usbhid_id, const struct pios_usb_hid_cfg * cfg, uint32_t lower_id) { - PIOS_Assert(usb_hid_id); + PIOS_Assert(usbhid_id); PIOS_Assert(cfg); struct pios_usb_hid_dev * usb_hid_dev; @@ -125,116 +127,24 @@ int32_t PIOS_USB_HID_Init(uint32_t * usb_hid_id, const struct pios_usb_hid_cfg * /* Bind the configuration to the device instance */ usb_hid_dev->cfg = cfg; + usb_hid_dev->lower_id = lower_id; - PIOS_USB_HID_Reenumerate(); - - /* - * This is a horrible hack to make this available to - * the interrupt callbacks. This should go away ASAP. - */ pios_usb_hid_id = (uint32_t) usb_hid_dev; - /* Enable the USB Interrupts */ - NVIC_Init(&usb_hid_dev->cfg->irq.init); + /* Bind lower level callbacks into the USB infrastructure */ + pEpInt_IN[cfg->data_tx_ep - 1] = PIOS_USB_HID_EP_IN_Callback; + pEpInt_OUT[cfg->data_rx_ep - 1] = PIOS_USB_HID_EP_OUT_Callback; - /* Select USBCLK source */ - RCC_USBCLKConfig(RCC_USBCLKSource_PLLCLK_1Div5); - /* Enable the USB clock */ - RCC_APB1PeriphClockCmd(RCC_APB1Periph_USB, ENABLE); + *usbhid_id = (uint32_t) usb_hid_dev; - /* Update the USB serial number from the chip */ - uint8_t sn[25]; - PIOS_SYS_SerialNumberGet((char *)sn); - for (uint8_t i = 0; sn[i] != '\0' && (2 * i) < PIOS_HID_StringSerial[0]; i++) { - PIOS_HID_StringSerial[2 + 2 * i] = sn[i]; - } - - USB_Init(); - USB_SIL_Init(); - - *usb_hid_id = (uint32_t) usb_hid_dev; - - return 0; /* No error */ + return 0; out_fail: - return(-1); + return -1; } -/** - * This function is called by the USB driver on cable connection/disconnection - * \param[in] connected connection status (1 if connected) - * \return < 0 on errors - * \note Applications shouldn't call this function directly, instead please use \ref PIOS_COM layer functions - */ -int32_t PIOS_USB_HID_ChangeConnectionState(uint32_t Connected) -{ - // In all cases: re-initialise USB HID driver - if (Connected) { - transfer_possible = 1; - //TODO: Check SetEPRxValid(ENDP1); -#if defined(USB_LED_ON) - USB_LED_ON; // turn the USB led on -#endif - } else { - // Cable disconnected: disable transfers - transfer_possible = 0; - -#if defined(USB_LED_OFF) - USB_LED_OFF; // turn the USB led off -#endif - } - - return 0; -} - -int32_t PIOS_USB_HID_Reenumerate() -{ - /* Force USB reset and power-down (this will also release the USB pins for direct GPIO control) */ - _SetCNTR(CNTR_FRES | CNTR_PDWN); - - /* Using a "dirty" method to force a re-enumeration: */ - /* Force DPM (Pin PA12) low for ca. 10 mS before USB Tranceiver will be enabled */ - /* This overrules the external Pull-Up at PA12, and at least Windows & MacOS will enumerate again */ - GPIO_InitTypeDef GPIO_InitStructure; - GPIO_StructInit(&GPIO_InitStructure); - GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12; - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; - GPIO_Init(GPIOA, &GPIO_InitStructure); - - PIOS_DELAY_WaitmS(50); - - /* Release power-down, still hold reset */ - _SetCNTR(CNTR_PDWN); - PIOS_DELAY_WaituS(5); - - /* CNTR_FRES = 0 */ - _SetCNTR(0); - - /* Clear pending interrupts */ - _SetISTR(0); - - /* Configure USB clock */ - /* USBCLK = PLLCLK / 1.5 */ - RCC_USBCLKConfig(RCC_USBCLKSource_PLLCLK_1Div5); - /* Enable USB clock */ - RCC_APB1PeriphClockCmd(RCC_APB1Periph_USB, ENABLE); - - return 0; -} - -/** - * This function returns the connection status of the USB HID interface - * \return 1: interface available - * \return 0: interface not available - * \note Applications shouldn't call this function directly, instead please use \ref PIOS_COM layer functions - */ -int32_t PIOS_USB_HID_CheckAvailable(uint8_t id) -{ - return (PIOS_USB_DETECT_GPIO_PORT->IDR & PIOS_USB_DETECT_GPIO_PIN) != 0 && transfer_possible ? 1 : 0; -} static void PIOS_USB_HID_SendReport(struct pios_usb_hid_dev * usb_hid_dev) { @@ -245,7 +155,7 @@ static void PIOS_USB_HID_SendReport(struct pios_usb_hid_dev * usb_hid_dev) } bool need_yield = false; -#ifdef USB_HID +#ifdef PIOS_USB_BOARD_BL_HID_HAS_NO_LENGTH_BYTE bytes_to_tx = (usb_hid_dev->tx_out_cb)(usb_hid_dev->tx_out_context, &usb_hid_dev->tx_packet_buffer[1], sizeof(usb_hid_dev->tx_packet_buffer)-1, @@ -265,15 +175,19 @@ static void PIOS_USB_HID_SendReport(struct pios_usb_hid_dev * usb_hid_dev) /* Always set type as report ID */ usb_hid_dev->tx_packet_buffer[0] = 1; -#ifdef USB_HID - UserToPMABufferCopy(usb_hid_dev->tx_packet_buffer, GetEPTxAddr(EP1_IN & 0x7F), bytes_to_tx + 1); +#ifdef PIOS_USB_BOARD_BL_HID_HAS_NO_LENGTH_BYTE + UserToPMABufferCopy(usb_hid_dev->tx_packet_buffer, + GetEPTxAddr(usb_hid_dev->cfg->data_tx_ep), + bytes_to_tx + 1); #else usb_hid_dev->tx_packet_buffer[1] = bytes_to_tx; - UserToPMABufferCopy(usb_hid_dev->tx_packet_buffer, GetEPTxAddr(EP1_IN & 0x7F), bytes_to_tx + 2); + UserToPMABufferCopy(usb_hid_dev->tx_packet_buffer, + GetEPTxAddr(usb_hid_dev->cfg->data_tx_ep), + bytes_to_tx + 2); #endif /* Is this correct? Why do we always send the whole buffer? */ - SetEPTxCount((EP1_IN & 0x7F), sizeof(usb_hid_dev->tx_packet_buffer)); - SetEPTxValid(ENDP1); + SetEPTxCount(usb_hid_dev->cfg->data_tx_ep, sizeof(usb_hid_dev->tx_packet_buffer)); + SetEPTxValid(usb_hid_dev->cfg->data_tx_ep); #if defined(PIOS_INCLUDE_FREERTOS) if (need_yield) { @@ -282,37 +196,43 @@ static void PIOS_USB_HID_SendReport(struct pios_usb_hid_dev * usb_hid_dev) #endif /* PIOS_INCLUDE_FREERTOS */ } -static void PIOS_USB_HID_RxStart(uint32_t usbcom_id, uint16_t rx_bytes_avail) { - struct pios_usb_hid_dev * usb_hid_dev = (struct pios_usb_hid_dev *)usbcom_id; +static void PIOS_USB_HID_RxStart(uint32_t usbhid_id, uint16_t rx_bytes_avail) { + struct pios_usb_hid_dev * usb_hid_dev = (struct pios_usb_hid_dev *)usbhid_id; bool valid = PIOS_USB_HID_validate(usb_hid_dev); PIOS_Assert(valid); - if (!transfer_possible) { + if (!PIOS_USB_CheckAvailable(usb_hid_dev->lower_id)) { return; } // If endpoint was stalled and there is now space make it valid +#ifdef PIOS_USB_BOARD_BL_HID_HAS_NO_LENGTH_BYTE + uint16_t max_payload_length = PIOS_USB_BOARD_HID_DATA_LENGTH - 1; +#else + uint16_t max_payload_length = PIOS_USB_BOARD_HID_DATA_LENGTH - 2; +#endif + PIOS_IRQ_Disable(); - if ((GetEPRxStatus(ENDP1) != EP_RX_VALID) && - (rx_bytes_avail > PIOS_USB_HID_DATA_LENGTH)) { - SetEPRxStatus(ENDP1, EP_RX_VALID); + if ((GetEPRxStatus(usb_hid_dev->cfg->data_rx_ep) != EP_RX_VALID) && + (rx_bytes_avail >= max_payload_length)) { + SetEPRxStatus(usb_hid_dev->cfg->data_rx_ep, EP_RX_VALID); } PIOS_IRQ_Enable(); } -static void PIOS_USB_HID_TxStart(uint32_t usbcom_id, uint16_t tx_bytes_avail) +static void PIOS_USB_HID_TxStart(uint32_t usbhid_id, uint16_t tx_bytes_avail) { - struct pios_usb_hid_dev * usb_hid_dev = (struct pios_usb_hid_dev *)usbcom_id; + struct pios_usb_hid_dev * usb_hid_dev = (struct pios_usb_hid_dev *)usbhid_id; bool valid = PIOS_USB_HID_validate(usb_hid_dev); PIOS_Assert(valid); - if (!transfer_possible) { + if (!PIOS_USB_CheckAvailable(usb_hid_dev->lower_id)) { return; } - if (GetEPTxStatus(ENDP1) == EP_TX_VALID) { + if (GetEPTxStatus(usb_hid_dev->cfg->data_tx_ep) == EP_TX_VALID) { /* Endpoint is already transmitting */ return; } @@ -320,9 +240,9 @@ static void PIOS_USB_HID_TxStart(uint32_t usbcom_id, uint16_t tx_bytes_avail) PIOS_USB_HID_SendReport(usb_hid_dev); } -static void PIOS_USB_HID_RegisterRxCallback(uint32_t usbcom_id, pios_com_callback rx_in_cb, uint32_t context) +static void PIOS_USB_HID_RegisterRxCallback(uint32_t usbhid_id, pios_com_callback rx_in_cb, uint32_t context) { - struct pios_usb_hid_dev * usb_hid_dev = (struct pios_usb_hid_dev *)usbcom_id; + struct pios_usb_hid_dev * usb_hid_dev = (struct pios_usb_hid_dev *)usbhid_id; bool valid = PIOS_USB_HID_validate(usb_hid_dev); PIOS_Assert(valid); @@ -335,9 +255,9 @@ static void PIOS_USB_HID_RegisterRxCallback(uint32_t usbcom_id, pios_com_callbac usb_hid_dev->rx_in_cb = rx_in_cb; } -static void PIOS_USB_HID_RegisterTxCallback(uint32_t usbcom_id, pios_com_callback tx_out_cb, uint32_t context) +static void PIOS_USB_HID_RegisterTxCallback(uint32_t usbhid_id, pios_com_callback tx_out_cb, uint32_t context) { - struct pios_usb_hid_dev * usb_hid_dev = (struct pios_usb_hid_dev *)usbcom_id; + struct pios_usb_hid_dev * usb_hid_dev = (struct pios_usb_hid_dev *)usbhid_id; bool valid = PIOS_USB_HID_validate(usb_hid_dev); PIOS_Assert(valid); @@ -354,14 +274,14 @@ static void PIOS_USB_HID_RegisterTxCallback(uint32_t usbcom_id, pios_com_callbac * @brief Callback used to indicate a transmission from device INto host completed * Checks if any data remains, pads it into HID packet and sends. */ -void PIOS_USB_HID_EP1_IN_Callback(void) +static void PIOS_USB_HID_EP_IN_Callback(void) { struct pios_usb_hid_dev * usb_hid_dev = (struct pios_usb_hid_dev *)pios_usb_hid_id; bool valid = PIOS_USB_HID_validate(usb_hid_dev); PIOS_Assert(valid); - if (!transfer_possible) { + if (!PIOS_USB_CheckAvailable(usb_hid_dev->lower_id)) { return; } @@ -371,35 +291,37 @@ void PIOS_USB_HID_EP1_IN_Callback(void) /** * EP1 OUT Callback Routine */ -void PIOS_USB_HID_EP1_OUT_Callback(void) +static void PIOS_USB_HID_EP_OUT_Callback(void) { struct pios_usb_hid_dev * usb_hid_dev = (struct pios_usb_hid_dev *)pios_usb_hid_id; bool valid = PIOS_USB_HID_validate(usb_hid_dev); PIOS_Assert(valid); - uint32_t DataLength = 0; + uint32_t DataLength; /* Read received data (63 bytes) */ /* Get the number of received data on the selected Endpoint */ - DataLength = GetEPRxCount(ENDP1 & 0x7F); + DataLength = GetEPRxCount(usb_hid_dev->cfg->data_rx_ep); if (DataLength > sizeof(usb_hid_dev->rx_packet_buffer)) { DataLength = sizeof(usb_hid_dev->rx_packet_buffer); } - /* Use the memory interface function to write to the selected endpoint */ - PMAToUserBufferCopy((uint8_t *) usb_hid_dev->rx_packet_buffer, GetEPRxAddr(ENDP1 & 0x7F), DataLength); + /* Use the memory interface function to read from the selected endpoint */ + PMAToUserBufferCopy((uint8_t *) usb_hid_dev->rx_packet_buffer, + GetEPRxAddr(usb_hid_dev->cfg->data_rx_ep), + DataLength); if (!usb_hid_dev->rx_in_cb) { /* No Rx call back registered, disable the receiver */ - SetEPRxStatus(ENDP1, EP_RX_NAK); + SetEPRxStatus(usb_hid_dev->cfg->data_rx_ep, EP_RX_NAK); return; } /* The first byte is report ID (not checked), the second byte is the valid data length */ uint16_t headroom; bool need_yield = false; -#ifdef USB_HID +#ifdef PIOS_USB_BOARD_BL_HID_HAS_NO_LENGTH_BYTE (usb_hid_dev->rx_in_cb)(usb_hid_dev->rx_in_context, &usb_hid_dev->rx_packet_buffer[1], sizeof(usb_hid_dev->rx_packet_buffer)-1, @@ -412,12 +334,20 @@ void PIOS_USB_HID_EP1_OUT_Callback(void) &headroom, &need_yield); #endif - if (headroom > PIOS_USB_HID_DATA_LENGTH) { + +#ifdef PIOS_USB_BOARD_BL_HID_HAS_NO_LENGTH_BYTE + uint16_t max_payload_length = PIOS_USB_BOARD_HID_DATA_LENGTH - 1; +#else + uint16_t max_payload_length = PIOS_USB_BOARD_HID_DATA_LENGTH - 2; +#endif + + if (headroom >= max_payload_length) { + /* We have room for a maximum length message */ - SetEPRxStatus(ENDP1, EP_RX_VALID); + SetEPRxStatus(usb_hid_dev->cfg->data_rx_ep, EP_RX_VALID); } else { /* Not enough room left for a message, apply backpressure */ - SetEPRxStatus(ENDP1, EP_RX_NAK); + SetEPRxStatus(usb_hid_dev->cfg->data_rx_ep, EP_RX_NAK); } #if defined(PIOS_INCLUDE_FREERTOS) @@ -427,9 +357,4 @@ void PIOS_USB_HID_EP1_OUT_Callback(void) #endif /* PIOS_INCLUDE_FREERTOS */ } -#endif - -/** - * @} - * @} - */ +#endif /* PIOS_INCLUDE_USB_HID */ diff --git a/flight/PiOS/STM32F10x/pios_usb_hid_desc.c b/flight/PiOS/STM32F10x/pios_usb_hid_desc.c deleted file mode 100644 index 8866e9e10..000000000 --- a/flight/PiOS/STM32F10x/pios_usb_hid_desc.c +++ /dev/null @@ -1,183 +0,0 @@ -/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** -* File Name : usb_desc.c -* Author : MCD Application Team -* Version : V3.2.1 -* Date : 07/05/2010 -* Description : Descriptors for Custom HID Demo -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ - -/* Includes ------------------------------------------------------------------*/ -#include "usb_lib.h" -#include "pios_usb.h" -#include "pios_usb_hid.h" -#include "pios_usb_hid_desc.h" - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Extern variables ----------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ - -/* USB Standard Device Descriptor */ -const uint8_t PIOS_HID_DeviceDescriptor[PIOS_HID_SIZ_DEVICE_DESC] = { - 0x12, /*bLength */ - USB_DEVICE_DESCRIPTOR_TYPE, /*bDescriptorType */ - 0x00, /*bcdUSB */ - 0x02, - 0x00, /*bDeviceClass */ - 0x00, /*bDeviceSubClass */ - 0x00, /*bDeviceProtocol */ - 0x40, /*bMaxPacketSize40 */ - (uint8_t) ((PIOS_USB_VENDOR_ID) & 0xff), /*idVendor */ - (uint8_t) ((PIOS_USB_VENDOR_ID) >> 8), - (uint8_t) ((PIOS_USB_PRODUCT_ID) & 0xff), /*idProduct */ - (uint8_t) ((PIOS_USB_PRODUCT_ID) >> 8), - (uint8_t) ((PIOS_USB_VERSION_ID) & 0xff), /*bcdDevice */ - (uint8_t) ((PIOS_USB_VERSION_ID) >> 8), - 0x01, /*Index of string descriptor describing - manufacturer */ - 0x02, /*Index of string descriptor describing - product */ - 0x03, /*Index of string descriptor describing the - device serial number */ - 0x01 /*bNumConfigurations */ -} - -; /* PIOS_HID_DeviceDescriptor */ - -/* USB Configuration Descriptor */ -/* All Descriptors (Configuration, Interface, Endpoint, Class, Vendor */ -const uint8_t PIOS_HID_ConfigDescriptor[PIOS_HID_SIZ_CONFIG_DESC] = { - 0x09, /* bLength: Configuation Descriptor size */ - USB_CONFIGURATION_DESCRIPTOR_TYPE, /* bDescriptorType: Configuration */ - PIOS_HID_SIZ_CONFIG_DESC, - /* wTotalLength: Bytes returned */ - 0x00, - 0x01, /* bNumInterfaces: 1 interface */ - 0x01, /* bConfigurationValue: Configuration value */ - 0x00, /* iConfiguration: Index of string descriptor describing - the configuration */ - 0xC0, /* bmAttributes: Bus powered */ - 0x32, /* MaxPower 100 mA: this current is used for detecting Vbus */ - - /************** Descriptor of Custom HID interface ****************/ - /* 09 */ - 0x09, /* bLength: Interface Descriptor size */ - USB_INTERFACE_DESCRIPTOR_TYPE, /* bDescriptorType: Interface descriptor type */ - 0x00, /* bInterfaceNumber: Number of Interface */ - 0x00, /* bAlternateSetting: Alternate setting */ - 0x02, /* bNumEndpoints */ - 0x03, /* bInterfaceClass: HID */ - 0x00, /* bInterfaceSubClass : 1=BOOT, 0=no boot */ - 0x00, /* nInterfaceProtocol : 0=none, 1=keyboard, 2=mouse */ - 0, /* iInterface: Index of string descriptor */ - /******************** Descriptor of Custom HID HID ********************/ - /* 18 */ - 0x09, /* bLength: HID Descriptor size */ - HID_DESCRIPTOR_TYPE, /* bDescriptorType: HID */ - 0x10, /* bcdHID: HID Class Spec release number */ - 0x01, - 0x00, /* bCountryCode: Hardware target country */ - 0x01, /* bNumDescriptors: Number of HID class descriptors to follow */ - 0x22, /* bDescriptorType */ - PIOS_HID_SIZ_REPORT_DESC, /* wItemLength: Total length of Report descriptor */ - 0x00, - /******************** Descriptor of Custom HID endpoints ******************/ - /* 27 */ - 0x07, /* bLength: Endpoint Descriptor size */ - USB_ENDPOINT_DESCRIPTOR_TYPE, /* bDescriptorType: */ - - 0x81, /* bEndpointAddress: Endpoint Address (IN) */ - 0x03, /* bmAttributes: Interrupt endpoint */ - 0x40, /* wMaxPacketSize: 2 Bytes max */ - 0x00, - 0x04, /* bInterval: Polling Interval (32 ms) */ - /* 34 */ - - 0x07, /* bLength: Endpoint Descriptor size */ - USB_ENDPOINT_DESCRIPTOR_TYPE, /* bDescriptorType: */ - /* Endpoint descriptor type */ - 0x01, /* bEndpointAddress: */ - /* Endpoint Address (OUT) */ - 0x03, /* bmAttributes: Interrupt endpoint */ - 0x40, /* wMaxPacketSize: 2 Bytes max */ - 0x00, - 0x04, /* bInterval: Polling Interval (20 ms) */ - /* 41 */ -} - -; /* PIOS_HID_ConfigDescriptor */ -const uint8_t PIOS_HID_ReportDescriptor[PIOS_HID_SIZ_REPORT_DESC] = { - 0x06, 0x9c, 0xff, /* USAGE_PAGE (Vendor Page: 0xFF00) */ - 0x09, 0x01, /* USAGE (Demo Kit) */ - 0xa1, 0x01, /* COLLECTION (Application) */ - /* 6 */ - - /* Data 1 */ - 0x85, 0x01, /* REPORT_ID (1) */ - 0x09, 0x02, /* USAGE (LED 1) */ - 0x15, 0x00, /* LOGICAL_MINIMUM (0) */ - 0x25, 0xff, /* LOGICAL_MAXIMUM (255) */ - 0x75, 0x08, /* REPORT_SIZE (8) */ - 0x95, PIOS_USB_HID_DATA_LENGTH + 1, /* REPORT_COUNT (1) */ - 0x81, 0x83, /* INPUT (Const,Var,Array) */ - /* 20 */ - - /* Data 1 */ - 0x85, 0x02, /* REPORT_ID (2) */ - 0x09, 0x03, /* USAGE (LED 1) */ - 0x15, 0x00, /* LOGICAL_MINIMUM (0) */ - 0x25, 0xff, /* LOGICAL_MAXIMUM (255) */ - 0x75, 0x08, /* REPORT_SIZE (8) */ - 0x95, PIOS_USB_HID_DATA_LENGTH + 1, /* REPORT_COUNT (1) */ - 0x91, 0x82, /* OUTPUT (Data,Var,Abs,Vol) */ - /* 34 */ - - 0xc0 /* END_COLLECTION */ -}; /* PIOS_HID_ReportDescriptor */ - -/* USB String Descriptors (optional) */ -const uint8_t PIOS_HID_StringLangID[PIOS_HID_SIZ_STRING_LANGID] = { - PIOS_HID_SIZ_STRING_LANGID, - USB_STRING_DESCRIPTOR_TYPE, - 0x09, - 0x04 -} - -; /* LangID = 0x0409: U.S. English */ - -const uint8_t PIOS_HID_StringVendor[PIOS_HID_SIZ_STRING_VENDOR] = { - PIOS_HID_SIZ_STRING_VENDOR, /* Size of Vendor string */ - USB_STRING_DESCRIPTOR_TYPE, /* bDescriptorType */ - /* Manufacturer: "STMicroelectronics" */ - 'o', 0, 'p', 0, 'e', 0, 'n', 0, 'p', 0, 'i', 0, 'l', 0, 'o', 0, - 't', 0, '.', 0, 'o', 0, 'r', 0, 'g', 0 -}; - -const uint8_t PIOS_HID_StringProduct[PIOS_HID_SIZ_STRING_PRODUCT] = { - PIOS_HID_SIZ_STRING_PRODUCT, /* bLength */ - USB_STRING_DESCRIPTOR_TYPE, /* bDescriptorType */ - 'O', 0, 'p', 0, 'e', 0, 'n', 0, 'P', 0, 'i', 0, 'l', 0, - 'o', 0, 't', 0 -}; - -uint8_t PIOS_HID_StringSerial[PIOS_HID_SIZ_STRING_SERIAL] = { - PIOS_HID_SIZ_STRING_SERIAL, /* bLength */ - USB_STRING_DESCRIPTOR_TYPE, /* bDescriptorType */ - 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 -}; - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/pios_usb_hid_istr.c b/flight/PiOS/STM32F10x/pios_usb_hid_istr.c index 1841705de..89204d07f 100644 --- a/flight/PiOS/STM32F10x/pios_usb_hid_istr.c +++ b/flight/PiOS/STM32F10x/pios_usb_hid_istr.c @@ -32,10 +32,10 @@ __IO uint8_t bIntPackSOF = 0; /* SOFs received between 2 consecutive packets */ /* Private functions ---------------------------------------------------------*/ /* function pointers to non-control endpoints service routines */ void (*pEpInt_IN[7]) (void) = { -PIOS_USB_HID_EP1_IN_Callback, EP2_IN_Callback, EP3_IN_Callback, EP4_IN_Callback, EP5_IN_Callback, EP6_IN_Callback, EP7_IN_Callback,}; +EP1_IN_Callback, EP2_IN_Callback, EP3_IN_Callback, EP4_IN_Callback, EP5_IN_Callback, EP6_IN_Callback, EP7_IN_Callback,}; void (*pEpInt_OUT[7]) (void) = { -PIOS_USB_HID_EP1_OUT_Callback, EP2_OUT_Callback, EP3_OUT_Callback, EP4_OUT_Callback, EP5_OUT_Callback, EP6_OUT_Callback, EP7_OUT_Callback,}; +EP1_OUT_Callback, EP2_OUT_Callback, EP3_OUT_Callback, EP4_OUT_Callback, EP5_OUT_Callback, EP6_OUT_Callback, EP7_OUT_Callback,}; #ifndef STM32F10X_CL diff --git a/flight/PiOS/STM32F10x/pios_usb_hid_prop.c b/flight/PiOS/STM32F10x/pios_usb_hid_prop.c deleted file mode 100644 index 9937053d0..000000000 --- a/flight/PiOS/STM32F10x/pios_usb_hid_prop.c +++ /dev/null @@ -1,408 +0,0 @@ -/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** -* File Name : usb_prop.c -* Author : MCD Application Team -* Version : V3.2.1 -* Date : 07/05/2010 -* Description : All processings related to Custom HID Demo -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f10x.h" -#include "usb_lib.h" -#include "usb_conf.h" -#include "pios.h" -#include "pios_usb_hid_prop.h" -#include "pios_usb_hid_desc.h" -#include "pios_usb_hid_pwr.h" -#include "pios_usb_hid.h" - -/* Private typedef -----------------------------------------------------------*/ -/* Private define ------------------------------------------------------------*/ -/* Private macro -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -uint32_t ProtocolValue; -__IO uint8_t EXTI_Enable; - -/* -------------------------------------------------------------------------- */ -/* Structures initializations */ -/* -------------------------------------------------------------------------- */ - -DEVICE Device_Table = { - EP_NUM, - 1 -}; - -DEVICE_PROP Device_Property = { - PIOS_HID_init, - PIOS_HID_Reset, - PIOS_HID_Status_In, - PIOS_HID_Status_Out, - PIOS_HID_Data_Setup, - PIOS_HID_NoData_Setup, - PIOS_HID_Get_Interface_Setting, - PIOS_HID_GetDeviceDescriptor, - PIOS_HID_GetConfigDescriptor, - PIOS_HID_GetStringDescriptor, - 0, - 0x40 /*MAX PACKET SIZE */ -}; - -USER_STANDARD_REQUESTS User_Standard_Requests = { - PIOS_HID_GetConfiguration, - PIOS_HID_SetConfiguration, - PIOS_HID_GetInterface, - PIOS_HID_SetInterface, - PIOS_HID_GetStatus, - PIOS_HID_ClearFeature, - PIOS_HID_SetEndPointFeature, - PIOS_HID_SetDeviceFeature, - PIOS_HID_SetDeviceAddress -}; - -ONE_DESCRIPTOR Device_Descriptor = { - (uint8_t *) PIOS_HID_DeviceDescriptor, - PIOS_HID_SIZ_DEVICE_DESC -}; - -ONE_DESCRIPTOR Config_Descriptor = { - (uint8_t *) PIOS_HID_ConfigDescriptor, - PIOS_HID_SIZ_CONFIG_DESC -}; - -ONE_DESCRIPTOR PIOS_HID_Report_Descriptor = { - (uint8_t *) PIOS_HID_ReportDescriptor, - PIOS_HID_SIZ_REPORT_DESC -}; - -ONE_DESCRIPTOR PIOS_HID_Hid_Descriptor = { - (uint8_t *) PIOS_HID_ConfigDescriptor + PIOS_HID_OFF_HID_DESC, - PIOS_HID_SIZ_HID_DESC -}; - -ONE_DESCRIPTOR String_Descriptor[4] = { - {(uint8_t *) PIOS_HID_StringLangID, PIOS_HID_SIZ_STRING_LANGID} - , - {(uint8_t *) PIOS_HID_StringVendor, PIOS_HID_SIZ_STRING_VENDOR} - , - {(uint8_t *) PIOS_HID_StringProduct, PIOS_HID_SIZ_STRING_PRODUCT} - , - {(uint8_t *) PIOS_HID_StringSerial, PIOS_HID_SIZ_STRING_SERIAL} -}; - -/* Extern variables ----------------------------------------------------------*/ -/* Private function prototypes -----------------------------------------------*/ -/* Extern function prototypes ------------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ - -/******************************************************************************* -* Function Name : PIOS_HID_init. -* Description : Custom HID init routine. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void PIOS_HID_init(void) -{ - /* Update the serial number string descriptor with the data from the unique - ID */ - //Get_SerialNum(); - - pInformation->Current_Configuration = 0; - /* Connect the device */ - PowerOn(); - - /* Perform basic device initialization operations */ - USB_SIL_Init(); - - bDeviceState = UNCONNECTED; -} - -/******************************************************************************* -* Function Name : PIOS_HID_Reset. -* Description : Custom HID reset routine. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void PIOS_HID_Reset(void) -{ - /* Set Joystick_DEVICE as not configured */ - pInformation->Current_Configuration = 0; - pInformation->Current_Interface = 0; /*the default Interface */ - - /* Current Feature initialization */ - pInformation->Current_Feature = PIOS_HID_ConfigDescriptor[7]; - -#ifdef STM32F10X_CL - /* EP0 is already configured in DFU_Init() by USB_SIL_Init() function */ - - /* Init EP1 IN as Interrupt endpoint */ - OTG_DEV_EP_Init(EP1_IN, OTG_DEV_EP_TYPE_INT, 2); - - /* Init EP1 OUT as Interrupt endpoint */ - OTG_DEV_EP_Init(EP1_OUT, OTG_DEV_EP_TYPE_INT, 2); -#else - SetBTABLE(BTABLE_ADDRESS); - - /* Initialize Endpoint 0 */ - SetEPType(ENDP0, EP_CONTROL); - SetEPTxStatus(ENDP0, EP_TX_STALL); - SetEPRxAddr(ENDP0, ENDP0_RXADDR); - SetEPTxAddr(ENDP0, ENDP0_TXADDR); - Clear_Status_Out(ENDP0); - SetEPRxCount(ENDP0, Device_Property.MaxPacketSize); - SetEPRxValid(ENDP0); - - /* Initialize Endpoint 1 */ - SetEPType(ENDP1, EP_INTERRUPT); - SetEPTxAddr(ENDP1, ENDP1_TXADDR); - SetEPRxAddr(ENDP1, ENDP1_RXADDR); - SetEPTxCount(ENDP1, PIOS_USB_HID_DATA_LENGTH + 2); /* add two for indicating report id and valid data length */ - SetEPRxCount(ENDP1, PIOS_USB_HID_DATA_LENGTH + 2); - SetEPRxStatus(ENDP1, EP_RX_VALID); - SetEPTxStatus(ENDP1, EP_TX_NAK); - - /* Set this device to response on default address */ - SetDeviceAddress(0); -#endif /* STM32F10X_CL */ - - bDeviceState = ATTACHED; -} - -/******************************************************************************* -* Function Name : PIOS_HID_SetConfiguration. -* Description : Udpade the device state to configured and command the ADC -* conversion. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void PIOS_HID_SetConfiguration(void) -{ - if (pInformation->Current_Configuration != 0) { - /* Device configured */ - bDeviceState = CONFIGURED; - } - - /* Enable transfers */ - PIOS_USB_HID_ChangeConnectionState(pInformation->Current_Configuration != 0); -} - -/******************************************************************************* -* Function Name : PIOS_HID_SetConfiguration. -* Description : Udpade the device state to addressed. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void PIOS_HID_SetDeviceAddress(void) -{ - bDeviceState = ADDRESSED; -} - -/******************************************************************************* -* Function Name : PIOS_HID_Status_In. -* Description : Joystick status IN routine. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void PIOS_HID_Status_In(void) -{ -} - -/******************************************************************************* -* Function Name : PIOS_HID_Status_Out -* Description : Joystick status OUT routine. -* Input : None. -* Output : None. -* Return : None. -*******************************************************************************/ -void PIOS_HID_Status_Out(void) -{ -} - -/******************************************************************************* -* Function Name : PIOS_HID_Data_Setup -* Description : Handle the data class specific requests. -* Input : Request Nb. -* Output : None. -* Return : USB_UNSUPPORT or USB_SUCCESS. -*******************************************************************************/ -RESULT PIOS_HID_Data_Setup(uint8_t RequestNo) -{ - uint8_t *(*CopyRoutine) (uint16_t); - - CopyRoutine = NULL; - - if ((RequestNo == GET_DESCRIPTOR) - && (Type_Recipient == (STANDARD_REQUEST | INTERFACE_RECIPIENT)) - && (pInformation->USBwIndex0 == 0)) { - - if (pInformation->USBwValue1 == REPORT_DESCRIPTOR) { - CopyRoutine = PIOS_HID_GetReportDescriptor; - } else if (pInformation->USBwValue1 == HID_DESCRIPTOR_TYPE) { - CopyRoutine = PIOS_HID_GetHIDDescriptor; - } - - } - - /* End of GET_DESCRIPTOR */ - /*** GET_PROTOCOL ***/ - else if ((Type_Recipient == (CLASS_REQUEST | INTERFACE_RECIPIENT)) - && RequestNo == GET_PROTOCOL) { - CopyRoutine = PIOS_HID_GetProtocolValue; - } - - if (CopyRoutine == NULL) { - return USB_UNSUPPORT; - } - - pInformation->Ctrl_Info.CopyData = CopyRoutine; - pInformation->Ctrl_Info.Usb_wOffset = 0; - (*CopyRoutine) (0); - return USB_SUCCESS; -} - -/******************************************************************************* -* Function Name : PIOS_HID_NoData_Setup -* Description : handle the no data class specific requests -* Input : Request Nb. -* Output : None. -* Return : USB_UNSUPPORT or USB_SUCCESS. -*******************************************************************************/ -RESULT PIOS_HID_NoData_Setup(uint8_t RequestNo) -{ - if ((Type_Recipient == (CLASS_REQUEST | INTERFACE_RECIPIENT)) - && (RequestNo == SET_PROTOCOL)) { - return PIOS_HID_SetProtocol(); - } - - else { - return USB_UNSUPPORT; - } -} - -/******************************************************************************* -* Function Name : PIOS_HID_GetDeviceDescriptor. -* Description : Gets the device descriptor. -* Input : Length -* Output : None. -* Return : The address of the device descriptor. -*******************************************************************************/ -uint8_t *PIOS_HID_GetDeviceDescriptor(uint16_t Length) -{ - return Standard_GetDescriptorData(Length, &Device_Descriptor); -} - -/******************************************************************************* -* Function Name : PIOS_HID_GetConfigDescriptor. -* Description : Gets the configuration descriptor. -* Input : Length -* Output : None. -* Return : The address of the configuration descriptor. -*******************************************************************************/ -uint8_t *PIOS_HID_GetConfigDescriptor(uint16_t Length) -{ - return Standard_GetDescriptorData(Length, &Config_Descriptor); -} - -/******************************************************************************* -* Function Name : PIOS_HID_GetStringDescriptor -* Description : Gets the string descriptors according to the needed index -* Input : Length -* Output : None. -* Return : The address of the string descriptors. -*******************************************************************************/ -uint8_t *PIOS_HID_GetStringDescriptor(uint16_t Length) -{ - uint8_t wValue0 = pInformation->USBwValue0; - if (wValue0 > 4) { - return NULL; - } else { - return Standard_GetDescriptorData(Length, &String_Descriptor[wValue0]); - } -} - -/******************************************************************************* -* Function Name : PIOS_HID_GetReportDescriptor. -* Description : Gets the HID report descriptor. -* Input : Length -* Output : None. -* Return : The address of the configuration descriptor. -*******************************************************************************/ -uint8_t *PIOS_HID_GetReportDescriptor(uint16_t Length) -{ - return Standard_GetDescriptorData(Length, &PIOS_HID_Report_Descriptor); -} - -/******************************************************************************* -* Function Name : PIOS_HID_GetHIDDescriptor. -* Description : Gets the HID descriptor. -* Input : Length -* Output : None. -* Return : The address of the configuration descriptor. -*******************************************************************************/ -uint8_t *PIOS_HID_GetHIDDescriptor(uint16_t Length) -{ - return Standard_GetDescriptorData(Length, &PIOS_HID_Hid_Descriptor); -} - -/******************************************************************************* -* Function Name : PIOS_HID_Get_Interface_Setting. -* Description : tests the interface and the alternate setting according to the -* supported one. -* Input : - Interface : interface number. -* - AlternateSetting : Alternate Setting number. -* Output : None. -* Return : USB_SUCCESS or USB_UNSUPPORT. -*******************************************************************************/ -RESULT PIOS_HID_Get_Interface_Setting(uint8_t Interface, uint8_t AlternateSetting) -{ - if (AlternateSetting > 0) { - return USB_UNSUPPORT; - } else if (Interface > 0) { - return USB_UNSUPPORT; - } - return USB_SUCCESS; -} - -/******************************************************************************* -* Function Name : PIOS_HID_SetProtocol -* Description : Joystick Set Protocol request routine. -* Input : None. -* Output : None. -* Return : USB SUCCESS. -*******************************************************************************/ -RESULT PIOS_HID_SetProtocol(void) -{ - uint8_t wValue0 = pInformation->USBwValue0; - ProtocolValue = wValue0; - return USB_SUCCESS; -} - -/******************************************************************************* -* Function Name : PIOS_HID_GetProtocolValue -* Description : get the protocol value -* Input : Length. -* Output : None. -* Return : address of the protcol value. -*******************************************************************************/ -uint8_t *PIOS_HID_GetProtocolValue(uint16_t Length) -{ - if (Length == 0) { - pInformation->Ctrl_Info.Usb_wLength = 1; - return NULL; - } else { - return (uint8_t *) (&ProtocolValue); - } -} - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F10x/pios_usbhook.c b/flight/PiOS/STM32F10x/pios_usbhook.c new file mode 100644 index 000000000..7800faed1 --- /dev/null +++ b/flight/PiOS/STM32F10x/pios_usbhook.c @@ -0,0 +1,516 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USBHOOK USB glue code + * @brief Glue between PiOS and STM32 libs + * @{ + * + * @file pios_usbhook.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Glue between PiOS and STM32 libs + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "pios.h" +#include "pios_usb.h" /* PIOS_USB_* */ +#include "pios_usbhook.h" +#include "pios_usb_defs.h" /* struct usb_* */ +#include "pios_usb_hid_pwr.h" +#include "pios_usb_cdc_priv.h" /* PIOS_USB_CDC_* */ +#include "pios_usb_board_data.h" /* PIOS_USB_BOARD_* */ + +static ONE_DESCRIPTOR Device_Descriptor; + +void PIOS_USBHOOK_RegisterDevice(const uint8_t * desc, uint16_t desc_size) +{ + Device_Descriptor.Descriptor = desc; + Device_Descriptor.Descriptor_Size = desc_size; +} + +static ONE_DESCRIPTOR Config_Descriptor; + +void PIOS_USBHOOK_RegisterConfig(uint8_t config_id, const uint8_t * desc, uint16_t desc_size) +{ + Config_Descriptor.Descriptor = desc; + Config_Descriptor.Descriptor_Size = desc_size; +} + +static ONE_DESCRIPTOR String_Descriptor[4]; + +void PIOS_USBHOOK_RegisterString(enum usb_string_desc string_id, const uint8_t * desc, uint16_t desc_size) +{ + if (string_id < NELEMENTS(String_Descriptor)) { + String_Descriptor[string_id].Descriptor = desc; + String_Descriptor[string_id].Descriptor_Size = desc_size; + } +} + +static ONE_DESCRIPTOR Hid_Interface_Descriptor; + +void PIOS_USBHOOK_RegisterHidInterface(const uint8_t * desc, uint16_t desc_size) +{ + Hid_Interface_Descriptor.Descriptor = desc; + Hid_Interface_Descriptor.Descriptor_Size = desc_size; +} + +static ONE_DESCRIPTOR Hid_Report_Descriptor; + +void PIOS_USBHOOK_RegisterHidReport(const uint8_t * desc, uint16_t desc_size) +{ + Hid_Report_Descriptor.Descriptor = desc; + Hid_Report_Descriptor.Descriptor_Size = desc_size; +} + +#include "stm32f10x.h" /* __IO */ +__IO uint8_t EXTI_Enable; + +uint32_t ProtocolValue; + +DEVICE Device_Table = { + PIOS_USB_BOARD_EP_NUM, + 1 +}; + +static void PIOS_USBHOOK_Init(void); +static void PIOS_USBHOOK_Reset(void); +static void PIOS_USBHOOK_Status_In(void); +static void PIOS_USBHOOK_Status_Out(void); +static RESULT PIOS_USBHOOK_Data_Setup(uint8_t RequestNo); +static RESULT PIOS_USBHOOK_NoData_Setup(uint8_t RequestNo); +static RESULT PIOS_USBHOOK_Get_Interface_Setting(uint8_t Interface, uint8_t AlternateSetting); +static const uint8_t *PIOS_USBHOOK_GetDeviceDescriptor(uint16_t Length); +static const uint8_t *PIOS_USBHOOK_GetConfigDescriptor(uint16_t Length); +static const uint8_t *PIOS_USBHOOK_GetStringDescriptor(uint16_t Length); + +DEVICE_PROP Device_Property = { + .Init = PIOS_USBHOOK_Init, + .Reset = PIOS_USBHOOK_Reset, + .Process_Status_IN = PIOS_USBHOOK_Status_In, + .Process_Status_OUT = PIOS_USBHOOK_Status_Out, + .Class_Data_Setup = PIOS_USBHOOK_Data_Setup, + .Class_NoData_Setup = PIOS_USBHOOK_NoData_Setup, + .Class_Get_Interface_Setting = PIOS_USBHOOK_Get_Interface_Setting, + .GetDeviceDescriptor = PIOS_USBHOOK_GetDeviceDescriptor, + .GetConfigDescriptor = PIOS_USBHOOK_GetConfigDescriptor, + .GetStringDescriptor = PIOS_USBHOOK_GetStringDescriptor, + .RxEP_buffer = 0, + .MaxPacketSize = 0x40, +}; + +static void PIOS_USBHOOK_SetConfiguration(void); +static void PIOS_USBHOOK_SetDeviceAddress(void); + +USER_STANDARD_REQUESTS User_Standard_Requests = { + .User_GetConfiguration = NOP_Process, + .User_SetConfiguration = PIOS_USBHOOK_SetConfiguration, + .User_GetInterface = NOP_Process, + .User_SetInterface = NOP_Process, + .User_GetStatus = NOP_Process, + .User_ClearFeature = NOP_Process, + .User_SetEndPointFeature = NOP_Process, + .User_SetDeviceFeature = NOP_Process, + .User_SetDeviceAddress = PIOS_USBHOOK_SetDeviceAddress +}; + +static RESULT PIOS_USBHOOK_SetProtocol(void); +static const uint8_t *PIOS_USBHOOK_GetProtocolValue(uint16_t Length); +static const uint8_t *PIOS_USBHOOK_GetReportDescriptor(uint16_t Length); +static const uint8_t *PIOS_USBHOOK_GetHIDDescriptor(uint16_t Length); + +/******************************************************************************* +* Function Name : PIOS_USBHOOK_Init. +* Description : Custom HID init routine. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +static void PIOS_USBHOOK_Init(void) +{ + pInformation->Current_Configuration = 0; + + /* Connect the device */ + PowerOn(); + + /* Perform basic device initialization operations */ + USB_SIL_Init(); + + bDeviceState = UNCONNECTED; +} + +/******************************************************************************* +* Function Name : PIOS_USBHOOK_Reset. +* Description : Custom HID reset routine. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +static void PIOS_USBHOOK_Reset(void) +{ + /* Set DEVICE as not configured */ + pInformation->Current_Configuration = 0; + pInformation->Current_Interface = 0; /*the default Interface */ + + /* Current Feature initialization */ + pInformation->Current_Feature = 0; + +#ifdef STM32F10X_CL + /* EP0 is already configured in DFU_Init() by USB_SIL_Init() function */ + + /* Init EP1 IN as Interrupt endpoint */ + OTG_DEV_EP_Init(EP1_IN, OTG_DEV_EP_TYPE_INT, 2); + + /* Init EP1 OUT as Interrupt endpoint */ + OTG_DEV_EP_Init(EP1_OUT, OTG_DEV_EP_TYPE_INT, 2); +#else + SetBTABLE(BTABLE_ADDRESS); + + /* Initialize Endpoint 0 (Control) */ + SetEPType(ENDP0, EP_CONTROL); + SetEPTxAddr(ENDP0, ENDP0_TXADDR); + SetEPTxStatus(ENDP0, EP_TX_STALL); + Clear_Status_Out(ENDP0); + + SetEPRxAddr(ENDP0, ENDP0_RXADDR); + SetEPRxCount(ENDP0, Device_Property.MaxPacketSize); + SetEPRxValid(ENDP0); + +#if defined(PIOS_INCLUDE_USB_HID) + /* Initialize Endpoint 1 (HID) */ + SetEPType(ENDP1, EP_INTERRUPT); + SetEPTxAddr(ENDP1, ENDP1_TXADDR); + SetEPTxCount(ENDP1, PIOS_USB_BOARD_HID_DATA_LENGTH); + SetEPTxStatus(ENDP1, EP_TX_NAK); + + SetEPRxAddr(ENDP1, ENDP1_RXADDR); + SetEPRxCount(ENDP1, PIOS_USB_BOARD_HID_DATA_LENGTH); + SetEPRxStatus(ENDP1, EP_RX_VALID); +#endif /* PIOS_INCLUDE_USB_HID */ + +#if defined(PIOS_INCLUDE_USB_CDC) + /* Initialize Endpoint 2 (CDC Call Control) */ + SetEPType(ENDP2, EP_INTERRUPT); + SetEPTxAddr(ENDP2, ENDP2_TXADDR); + SetEPTxStatus(ENDP2, EP_TX_NAK); + + SetEPRxAddr(ENDP2, ENDP2_RXADDR); + SetEPRxCount(ENDP2, PIOS_USB_BOARD_CDC_MGMT_LENGTH); + SetEPRxStatus(ENDP2, EP_RX_DIS); + + /* Initialize Endpoint 3 (CDC Data) */ + SetEPType(ENDP3, EP_BULK); + SetEPTxAddr(ENDP3, ENDP3_TXADDR); + SetEPTxStatus(ENDP3, EP_TX_NAK); + + SetEPRxAddr(ENDP3, ENDP3_RXADDR); + SetEPRxCount(ENDP3, PIOS_USB_BOARD_CDC_DATA_LENGTH); + SetEPRxStatus(ENDP3, EP_RX_VALID); + +#endif /* PIOS_INCLUDE_USB_CDC */ + + /* Set this device to response on default address */ + SetDeviceAddress(0); +#endif /* STM32F10X_CL */ + + bDeviceState = ATTACHED; +} + +/******************************************************************************* +* Function Name : PIOS_USBHOOK_SetConfiguration. +* Description : Update the device state to configured +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +static void PIOS_USBHOOK_SetConfiguration(void) +{ + if (pInformation->Current_Configuration != 0) { + /* Device configured */ + bDeviceState = CONFIGURED; + } + + /* Enable transfers */ + PIOS_USB_ChangeConnectionState(pInformation->Current_Configuration != 0); +} + +/******************************************************************************* +* Function Name : PIOS_USBHOOK_SetConfiguration. +* Description : Update the device state to addressed. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +static void PIOS_USBHOOK_SetDeviceAddress(void) +{ + bDeviceState = ADDRESSED; +} + +/******************************************************************************* +* Function Name : PIOS_USBHOOK_Status_In. +* Description : status IN routine. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +static void PIOS_USBHOOK_Status_In(void) +{ +} + +/******************************************************************************* +* Function Name : PIOS_USBHOOK_Status_Out +* Description : status OUT routine. +* Input : None. +* Output : None. +* Return : None. +*******************************************************************************/ +static void PIOS_USBHOOK_Status_Out(void) +{ +} + +/******************************************************************************* +* Function Name : PIOS_USBHOOK_Data_Setup +* Description : Handle the data class specific requests. +* Input : Request Nb. +* Output : None. +* Return : USB_UNSUPPORT or USB_SUCCESS. +*******************************************************************************/ +static RESULT PIOS_USBHOOK_Data_Setup(uint8_t RequestNo) +{ + const uint8_t *(*CopyRoutine) (uint16_t); + + CopyRoutine = NULL; + + switch (Type_Recipient) { + case (STANDARD_REQUEST | INTERFACE_RECIPIENT): + switch (pInformation->USBwIndex0) { + case 0: /* HID Interface */ + switch (RequestNo) { + case GET_DESCRIPTOR: + switch (pInformation->USBwValue1) { + case USB_DESC_TYPE_REPORT: + CopyRoutine = PIOS_USBHOOK_GetReportDescriptor; + break; + case USB_DESC_TYPE_HID: + CopyRoutine = PIOS_USBHOOK_GetHIDDescriptor; + break; + } + } + } + break; + + case (CLASS_REQUEST | INTERFACE_RECIPIENT): + switch (pInformation->USBwIndex0) { + case 0: /* HID Interface */ + switch (RequestNo) { + case GET_PROTOCOL: + CopyRoutine = PIOS_USBHOOK_GetProtocolValue; + break; + } + + break; +#if defined(PIOS_INCLUDE_USB_CDC) + case 1: /* CDC Call Control Interface */ + switch (RequestNo) { + case GET_LINE_CODING: + CopyRoutine = PIOS_USB_CDC_GetLineCoding; + break; + } + + break; + + case 2: /* CDC Data Interface */ + switch (RequestNo) { + case 0: + break; + } + + break; +#endif /* PIOS_INCLUDE_USB_CDC */ + } + break; + } + + if (CopyRoutine == NULL) { + return USB_UNSUPPORT; + } + + pInformation->Ctrl_Info.CopyDataIn = CopyRoutine; + pInformation->Ctrl_Info.Usb_wOffset = 0; + (*CopyRoutine) (0); + return USB_SUCCESS; +} + +/******************************************************************************* +* Function Name : PIOS_USBHOOK_NoData_Setup +* Description : handle the no data class specific requests +* Input : Request Nb. +* Output : None. +* Return : USB_UNSUPPORT or USB_SUCCESS. +*******************************************************************************/ +static RESULT PIOS_USBHOOK_NoData_Setup(uint8_t RequestNo) +{ + switch (Type_Recipient) { + case (CLASS_REQUEST | INTERFACE_RECIPIENT): + switch (pInformation->USBwIndex0) { + case 0: /* HID */ + switch (RequestNo) { + case SET_PROTOCOL: + return PIOS_USBHOOK_SetProtocol(); + break; + } + + break; + +#if defined(PIOS_INCLUDE_USB_CDC) + case 1: /* CDC Call Control Interface */ + switch (RequestNo) { + case SET_LINE_CODING: + return PIOS_USB_CDC_SetLineCoding(); + break; + case SET_CONTROL_LINE_STATE: + return PIOS_USB_CDC_SetControlLineState(); + break; + } + + break; +#endif /* PIOS_INCLUDE_USB_CDC */ + } + + break; + } + + return USB_UNSUPPORT; +} + +/******************************************************************************* +* Function Name : PIOS_USBHOOK_GetDeviceDescriptor. +* Description : Gets the device descriptor. +* Input : Length +* Output : None. +* Return : The address of the device descriptor. +*******************************************************************************/ +static const uint8_t *PIOS_USBHOOK_GetDeviceDescriptor(uint16_t Length) +{ + return Standard_GetDescriptorData(Length, &Device_Descriptor); +} + +/******************************************************************************* +* Function Name : PIOS_USBHOOK_GetConfigDescriptor. +* Description : Gets the configuration descriptor. +* Input : Length +* Output : None. +* Return : The address of the configuration descriptor. +*******************************************************************************/ +static const uint8_t *PIOS_USBHOOK_GetConfigDescriptor(uint16_t Length) +{ + return Standard_GetDescriptorData(Length, &Config_Descriptor); +} + +/******************************************************************************* +* Function Name : PIOS_USBHOOK_GetStringDescriptor +* Description : Gets the string descriptors according to the needed index +* Input : Length +* Output : None. +* Return : The address of the string descriptors. +*******************************************************************************/ +static const uint8_t *PIOS_USBHOOK_GetStringDescriptor(uint16_t Length) +{ + uint8_t wValue0 = pInformation->USBwValue0; + if (wValue0 > 4) { + return NULL; + } else { + return Standard_GetDescriptorData(Length, &String_Descriptor[wValue0]); + } +} + +/******************************************************************************* +* Function Name : PIOS_USBHOOK_GetReportDescriptor. +* Description : Gets the HID report descriptor. +* Input : Length +* Output : None. +* Return : The address of the configuration descriptor. +*******************************************************************************/ +static const uint8_t *PIOS_USBHOOK_GetReportDescriptor(uint16_t Length) +{ + return Standard_GetDescriptorData(Length, &Hid_Report_Descriptor); +} + +/******************************************************************************* +* Function Name : PIOS_USBHOOK_GetHIDDescriptor. +* Description : Gets the HID descriptor. +* Input : Length +* Output : None. +* Return : The address of the configuration descriptor. +*******************************************************************************/ +static const uint8_t *PIOS_USBHOOK_GetHIDDescriptor(uint16_t Length) +{ + return Standard_GetDescriptorData(Length, &Hid_Interface_Descriptor); +} + +/******************************************************************************* +* Function Name : PIOS_USBHOOK_Get_Interface_Setting. +* Description : tests the interface and the alternate setting according to the +* supported one. +* Input : - Interface : interface number. +* - AlternateSetting : Alternate Setting number. +* Output : None. +* Return : USB_SUCCESS or USB_UNSUPPORT. +*******************************************************************************/ +static RESULT PIOS_USBHOOK_Get_Interface_Setting(uint8_t Interface, uint8_t AlternateSetting) +{ + if (AlternateSetting > 0) { + return USB_UNSUPPORT; + } else if (Interface > 0) { + return USB_UNSUPPORT; + } + return USB_SUCCESS; +} + +/******************************************************************************* +* Function Name : PIOS_USBHOOK_SetProtocol +* Description : Set Protocol request routine. +* Input : None. +* Output : None. +* Return : USB SUCCESS. +*******************************************************************************/ +static RESULT PIOS_USBHOOK_SetProtocol(void) +{ + uint8_t wValue0 = pInformation->USBwValue0; + ProtocolValue = wValue0; + return USB_SUCCESS; +} + +/******************************************************************************* +* Function Name : PIOS_USBHOOK_GetProtocolValue +* Description : get the protocol value +* Input : Length. +* Output : None. +* Return : address of the protcol value. +*******************************************************************************/ +static const uint8_t *PIOS_USBHOOK_GetProtocolValue(uint16_t Length) +{ + if (Length == 0) { + pInformation->Ctrl_Info.Usb_wLength = 1; + return NULL; + } else { + return (uint8_t *) (&ProtocolValue); + } +} + +/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/STM32F4xx/pios_bmp085.c b/flight/PiOS/STM32F4xx/pios_bmp085.c index 37aa405cb..2b597794d 100644 --- a/flight/PiOS/STM32F4xx/pios_bmp085.c +++ b/flight/PiOS/STM32F4xx/pios_bmp085.c @@ -38,7 +38,16 @@ /* Glocal Variables */ ConversionTypeTypeDef CurrentRead; -int32_t pios_bmp085_eoc; + +#ifdef PIOS_BMP085_HAS_GPIOS + +#if defined(PIOS_INCLUDE_FREERTOS) +xSemaphoreHandle PIOS_BMP085_EOC; +#else +int32_t PIOS_BMP085_EOC; +#endif + +#endif /* PIOS_BMP085_HAS_GPIOS */ /* Local Variables */ static BMP085CalibDataTypeDef CalibData; @@ -63,7 +72,28 @@ static const struct pios_bmp085_cfg * dev_cfg; */ void PIOS_BMP085_Init(const struct pios_bmp085_cfg * cfg) { +<<<<<<< HEAD pios_bmp085_eoc = 0; +======= + +#ifdef PIOS_BMP085_HAS_GPIOS + + GPIO_InitTypeDef GPIO_InitStructure; + EXTI_InitTypeDef EXTI_InitStructure; + NVIC_InitTypeDef NVIC_InitStructure; + +#if defined(PIOS_INCLUDE_FREERTOS) + /* Semaphore used by ISR to signal End-Of-Conversion */ + vSemaphoreCreateBinary(PIOS_BMP085_EOC); + /* Must start off empty so that first transfer waits for EOC */ + xSemaphoreTake(PIOS_BMP085_EOC, portMAX_DELAY); +#else + PIOS_BMP085_EOC = 0; +#endif + + /* Enable EOC GPIO clock */ + RCC_APB2PeriphClockCmd(PIOS_BMP085_EOC_CLK | RCC_APB2Periph_AFIO, ENABLE); +>>>>>>> next oversampling = cfg->oversampling; dev_cfg = cfg; // Store cfg before enabling interrupt @@ -78,10 +108,15 @@ void PIOS_BMP085_Init(const struct pios_bmp085_cfg * cfg) /* Enable and set EOC EXTI Interrupt to the lowest priority */ NVIC_Init(&cfg->eoc_irq.init); +<<<<<<< HEAD /* Configure anothing GPIO pin pin as output to set address */ GPIO_Init(cfg->xclr.gpio, &cfg->xclr.init); GPIO_SetBits(cfg->xclr.gpio,cfg->xclr.init.GPIO_Pin); +======= +#endif /* PIOS_BMP085_HAS_GPIOS */ + +>>>>>>> next /* Read all 22 bytes of calibration data in one transfer, this is a very optimized way of doing things */ uint8_t Data[BMP085_CALIB_LEN]; bool good_cal = false; @@ -232,7 +267,7 @@ int32_t PIOS_BMP085_Read(uint8_t address, uint8_t * buffer, uint8_t len) } }; - return PIOS_I2C_Transfer(PIOS_I2C_MAIN_ADAPTER, txn_list, NELEMENTS(txn_list)); + return PIOS_I2C_Transfer(PIOS_I2C_BMP085_ADAPTER, txn_list, NELEMENTS(txn_list)); } /** @@ -260,7 +295,7 @@ int32_t PIOS_BMP085_Write(uint8_t address, uint8_t buffer) , }; - return PIOS_I2C_Transfer(PIOS_I2C_MAIN_ADAPTER, txn_list, NELEMENTS(txn_list)); + return PIOS_I2C_Transfer(PIOS_I2C_BMP085_ADAPTER, txn_list, NELEMENTS(txn_list)); } /** diff --git a/flight/PiOS/STM32F4xx/pios_iap.c b/flight/PiOS/STM32F4xx/pios_iap.c index e7d1a61b3..004be298a 100644 --- a/flight/PiOS/STM32F4xx/pios_iap.c +++ b/flight/PiOS/STM32F4xx/pios_iap.c @@ -1,159 +1,153 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_IAP IAP Functions - * @brief STM32F4xx Hardware dependent I2C functionality - * @{ - * - * @file pios_iap.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @brief In application programming functions - * @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 - */ - -/**************************************************************************************** - * Header files - ****************************************************************************************/ -#include - -/**************************************************************************************** - * Private Definitions/Macros - ****************************************************************************************/ - -/* these definitions reside here for protection and privacy. */ -#define IAP_MAGIC_WORD_1 0x1122 -#define IAP_MAGIC_WORD_2 0xAA55 - -#define IAP_REQLOC_1 BKP_DR1 -#define IAP_CRCLOC_LOW BKP_DR2 -#define IAP_CRCLOC_UPPER BKP_DR3 -#define IAP_PORTLOC BKP_DR4 -#define IAP_REQLOC_2 BKP_RR5 - -#define IAP_UPLOAD_REQ_1 0x20AA -#define IAP_UPLOAD_REQ_2 0x2055 -#define IAP_DNLOAD_REQ_1 0x30AA -#define IAP_DNLOAD_REQ_2 0x3055 - -#define UPPERWORD16(lw) (uint16_t)((uint32_t)(lw)>>16) -#define LOWERWORD16(lw) (uint16_t)((uint32_t)(lw)&0x0000ffff) -#define UPPERBYTE(w) (uint8_t)((w)>>8) -#define LOWERBYTE(w) (uint8_t)((w)&0x00ff) - -/**************************************************************************************** - * Private Functions - ****************************************************************************************/ - -/**************************************************************************************** - * Private (static) Data - ****************************************************************************************/ - -/**************************************************************************************** - * Public/Global Data - ****************************************************************************************/ - -/*! - * \brief PIOS_IAP_Init - performs required initializations for iap module. - * \param none. - * \return none. - * \retval none. - * - * Created: Sep 8, 2010 10:10:48 PM by joe - */ -void PIOS_IAP_Init( void ) -{ -#if 0 - /* Enable CRC clock */ - RCC_AHBPeriphClockCmd(RCC_AHBPeriph_CRC, ENABLE); - - /* Enable PWR and BKP clock */ - RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR | RCC_APB1Periph_BKP, ENABLE); - - /* Enable write access to Backup domain */ - PWR_BackupAccessCmd(ENABLE); - - /* Clear Tamper pin Event(TE) pending flag */ - BKP_ClearFlag(); -#endif -} - -/*! - * \brief Determines if an In-Application-Programming request has been made. - * \param *comm - Which communication stream to use for the IAP (USB, Telemetry, I2C, SPI, etc) - * \return TRUE - if correct sequence found, along with 'comm' updated. - * FALSE - Note that 'comm' will have an invalid comm identifier. - * \retval - * - */ -uint32_t PIOS_IAP_CheckRequest( void ) -{ -#if 0 - uint32_t retval = FALSE; - uint16_t reg1; - uint16_t reg2; - - reg1 = BKP_ReadBackupRegister( MAGIC_REG_1 ); - reg2 = BKP_ReadBackupRegister( MAGIC_REG_2 ); - - if( reg1 == IAP_MAGIC_WORD_1 && reg2 == IAP_MAGIC_WORD_2 ) { - // We have a match. - retval = TRUE; - } else { - retval = FALSE; - } - return retval; -#endif - return 0; -} - - - -/*! - * \brief Sets the 1st word of the request sequence. - * \param n/a - * \return n/a - * \retval - */ -void PIOS_IAP_SetRequest1(void) -{ -#if 0 - BKP_WriteBackupRegister( MAGIC_REG_1, IAP_MAGIC_WORD_1); -#endif -} - -void PIOS_IAP_SetRequest2(void) -{ -#if 0 - BKP_WriteBackupRegister( MAGIC_REG_2, IAP_MAGIC_WORD_2); -#endif -} - -void PIOS_IAP_ClearRequest(void) -{ -#if 0 - BKP_WriteBackupRegister( MAGIC_REG_1, 0); - BKP_WriteBackupRegister( MAGIC_REG_2, 0); -#endif -} - -/** - * @} - * @} - */ \ No newline at end of file +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_IAP IAP Functions + * @brief STM32F4xx Hardware dependent I2C functionality + * @{ + * + * @file pios_iap.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief In application programming functions + * @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 + */ + +/**************************************************************************************** + * Header files + ****************************************************************************************/ +#include + +/**************************************************************************************** + * Private Definitions/Macros + ****************************************************************************************/ + +/* these definitions reside here for protection and privacy. */ +#define IAP_MAGIC_WORD_1 0x1122 +#define IAP_MAGIC_WORD_2 0xAA55 + +#define UPPERWORD16(lw) (uint16_t)((uint32_t)(lw)>>16) +#define LOWERWORD16(lw) (uint16_t)((uint32_t)(lw)&0x0000ffff) +#define UPPERBYTE(w) (uint8_t)((w)>>8) +#define LOWERBYTE(w) (uint8_t)((w)&0x00ff) + +/**************************************************************************************** + * Private Functions + ****************************************************************************************/ + +/**************************************************************************************** + * Private (static) Data + ****************************************************************************************/ + +/**************************************************************************************** + * Public/Global Data + ****************************************************************************************/ + +/*! + * \brief PIOS_IAP_Init - performs required initializations for iap module. + * \param none. + * \return none. + * \retval none. + * + * Created: Sep 8, 2010 10:10:48 PM by joe + */ +void PIOS_IAP_Init( void ) +{ +#if 0 + /* Enable CRC clock */ + RCC_AHBPeriphClockCmd(RCC_AHBPeriph_CRC, ENABLE); + + /* Enable PWR and BKP clock */ + RCC_APB1PeriphClockCmd(RCC_APB1Periph_PWR | RCC_APB1Periph_BKP, ENABLE); + + /* Enable write access to Backup domain */ + PWR_BackupAccessCmd(ENABLE); + + /* Clear Tamper pin Event(TE) pending flag */ + BKP_ClearFlag(); +#endif +} + +/*! + * \brief Determines if an In-Application-Programming request has been made. + * \param *comm - Which communication stream to use for the IAP (USB, Telemetry, I2C, SPI, etc) + * \return TRUE - if correct sequence found, along with 'comm' updated. + * FALSE - Note that 'comm' will have an invalid comm identifier. + * \retval + * + */ +uint32_t PIOS_IAP_CheckRequest( void ) +{ +#if 0 + uint32_t retval = FALSE; + uint16_t reg1; + uint16_t reg2; + + reg1 = BKP_ReadBackupRegister( MAGIC_REG_1 ); + reg2 = BKP_ReadBackupRegister( MAGIC_REG_2 ); + + if( reg1 == IAP_MAGIC_WORD_1 && reg2 == IAP_MAGIC_WORD_2 ) { + // We have a match. + retval = TRUE; + } else { + retval = FALSE; + } + return retval; +#endif + return 0; +} + + + +/*! + * \brief Sets the 1st word of the request sequence. + * \param n/a + * \return n/a + * \retval + */ +void PIOS_IAP_SetRequest1(void) +{ +#if 0 + BKP_WriteBackupRegister( MAGIC_REG_1, IAP_MAGIC_WORD_1); +#endif +} + +void PIOS_IAP_SetRequest2(void) +{ +#if 0 + BKP_WriteBackupRegister( MAGIC_REG_2, IAP_MAGIC_WORD_2); +#endif +} + +void PIOS_IAP_ClearRequest(void) +{ +#if 0 + BKP_WriteBackupRegister( MAGIC_REG_1, 0); + BKP_WriteBackupRegister( MAGIC_REG_2, 0); +#endif +} + +uint16_t PIOS_IAP_ReadBootCount(void) +{ + return BKP_ReadBackupRegister ( IAP_BOOTCOUNT ); +} + +void PIOS_IAP_WriteBootCount (uint16_t boot_count) +{ + BKP_WriteBackupRegister ( IAP_BOOTCOUNT, boot_count ); +} diff --git a/flight/PiOS/inc/pios_com.h b/flight/PiOS/inc/pios_com.h index cbee33735..10591f116 100644 --- a/flight/PiOS/inc/pios_com.h +++ b/flight/PiOS/inc/pios_com.h @@ -8,7 +8,6 @@ * * @file pios_com.h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) * @brief COM layer functions header * @see The GNU Public License (GPL) Version 3 * @@ -32,6 +31,9 @@ #ifndef PIOS_COM_H #define PIOS_COM_H +#include /* uint*_t */ +#include /* bool */ + typedef uint16_t (*pios_com_callback)(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, bool * task_woken); struct pios_com_driver { @@ -44,7 +46,6 @@ struct pios_com_driver { }; /* Public Functions */ -extern int32_t PIOS_COM_Init(uint32_t * com_id, const struct pios_com_driver * driver, uint32_t lower_id, uint8_t * rx_buffer, uint16_t rx_buffer_len, uint8_t * tx_buffer, uint16_t tx_buffer_len); extern int32_t PIOS_COM_ChangeBaud(uint32_t com_id, uint32_t baud); extern int32_t PIOS_COM_SendCharNonBlocking(uint32_t com_id, char c); extern int32_t PIOS_COM_SendChar(uint32_t com_id, char c); @@ -55,7 +56,6 @@ extern int32_t PIOS_COM_SendString(uint32_t com_id, const char *str); extern int32_t PIOS_COM_SendFormattedStringNonBlocking(uint32_t com_id, const char *format, ...); extern int32_t PIOS_COM_SendFormattedString(uint32_t com_id, const char *format, ...); extern uint16_t PIOS_COM_ReceiveBuffer(uint32_t com_id, uint8_t * buf, uint16_t buf_len, uint32_t timeout_ms); -extern int32_t PIOS_COM_ReceiveBufferUsed(uint32_t com_id); #endif /* PIOS_COM_H */ diff --git a/flight/PiOS/inc/pios_com_msg.h b/flight/PiOS/inc/pios_com_msg.h new file mode 100644 index 000000000..1caaeabeb --- /dev/null +++ b/flight/PiOS/inc/pios_com_msg.h @@ -0,0 +1,45 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_COM COM MSG layer functions + * @brief Hardware communication layer + * @{ + * + * @file pios_com_msg.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief COM MSG layer functions header + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_COM_MSG_H +#define PIOS_COM_MSG_H + +#include /* uint*_t */ + +/* Public Functions */ +extern int32_t PIOS_COM_MSG_Send(uint32_t com_id, const uint8_t *msg, uint16_t msg_len); +extern uint16_t PIOS_COM_MSG_Receive(uint32_t com_id, uint8_t * buf, uint16_t buf_len); + +#endif /* PIOS_COM_MSG_H */ + +/** + * @} + * @} + */ diff --git a/flight/PiOS/inc/pios_com_msg_priv.h b/flight/PiOS/inc/pios_com_msg_priv.h new file mode 100644 index 000000000..20992de47 --- /dev/null +++ b/flight/PiOS/inc/pios_com_msg_priv.h @@ -0,0 +1,44 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_COM COM MSG layer functions + * @brief Hardware communication layer + * @{ + * + * @file pios_com_msg_priv.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief COM MSG private definitions. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_COM_MSG_PRIV_H +#define PIOS_COM_MSG_PRIV_H + +#include /* uint*_t */ +#include "pios_com_priv.h" /* struct pios_com_driver */ + +extern int32_t PIOS_COM_MSG_Init(uint32_t * com_id, const struct pios_com_driver * driver, uint32_t lower_id); + +#endif /* PIOS_COM_MSG_PRIV_H */ + +/** + * @} + * @} + */ diff --git a/flight/PiOS/inc/pios_com_priv.h b/flight/PiOS/inc/pios_com_priv.h index 54af82bcb..c39522f79 100644 --- a/flight/PiOS/inc/pios_com_priv.h +++ b/flight/PiOS/inc/pios_com_priv.h @@ -8,7 +8,6 @@ * * @file pios_com_priv.h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) * @brief COM private definitions. * @see The GNU Public License (GPL) Version 3 * @@ -32,9 +31,7 @@ #ifndef PIOS_COM_PRIV_H #define PIOS_COM_PRIV_H -#include - -extern int32_t PIOS_COM_ReceiveHandler(uint32_t com_id); +extern int32_t PIOS_COM_Init(uint32_t * com_id, const struct pios_com_driver * driver, uint32_t lower_id, uint8_t * rx_buffer, uint16_t rx_buffer_len, uint8_t * tx_buffer, uint16_t tx_buffer_len); #endif /* PIOS_COM_PRIV_H */ diff --git a/flight/PiOS/inc/pios_delay.h b/flight/PiOS/inc/pios_delay.h index 60ca98d1c..4b79e3ef1 100644 --- a/flight/PiOS/inc/pios_delay.h +++ b/flight/PiOS/inc/pios_delay.h @@ -8,7 +8,6 @@ * * @file pios_settings.h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) * @brief Settings functions header * @see The GNU Public License (GPL) Version 3 * diff --git a/flight/PiOS/inc/pios_i2c.h b/flight/PiOS/inc/pios_i2c.h index e1a5f0171..b34acf9e6 100644 --- a/flight/PiOS/inc/pios_i2c.h +++ b/flight/PiOS/inc/pios_i2c.h @@ -7,7 +7,6 @@ * * @file pios_i2c.h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) * @brief I2C functions header. * @see The GNU Public License (GPL) Version 3 * diff --git a/flight/PiOS/inc/pios_i2c_priv.h b/flight/PiOS/inc/pios_i2c_priv.h index e20268589..9daf7cdd3 100644 --- a/flight/PiOS/inc/pios_i2c_priv.h +++ b/flight/PiOS/inc/pios_i2c_priv.h @@ -3,7 +3,6 @@ * * @file pios_i2c_priv.h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) * @brief I2C private definitions. * @see The GNU Public License (GPL) Version 3 * @@ -39,6 +38,7 @@ struct pios_i2c_adapter_cfg { uint32_t transfer_timeout_ms; struct stm32_gpio scl; struct stm32_gpio sda; + uint32_t remap; struct stm32_irq event; struct stm32_irq error; }; diff --git a/flight/PiOS/inc/pios_iap.h b/flight/PiOS/inc/pios_iap.h index aae0132f0..1f67d651f 100644 --- a/flight/PiOS/inc/pios_iap.h +++ b/flight/PiOS/inc/pios_iap.h @@ -19,27 +19,18 @@ ****************************************************************************************/ #define MAGIC_REG_1 BKP_DR1 #define MAGIC_REG_2 BKP_DR2 -#define IAP_COMM BKP_DR3 - -#define IAP_COMM_INVALID 0 -#define IAP_COMM_USB 1 -#define IAP_COMM_TELEMETRY 2 -#define IAP_COMM_SPI_AHRS 3 -#define IAP_COMM_I2C 4 -// Additional types can be added along with the proper support code. +#define IAP_BOOTCOUNT BKP_DR3 /**************************************************************************************** * Public Functions ****************************************************************************************/ void PIOS_IAP_Init(void); -uint32_t PIOS_IAP_CRCVerify( void ); uint32_t PIOS_IAP_CheckRequest( void ); -void PIOS_IAP_SetCommInput( uint16_t comm ); -uint16_t PIOS_IAP_GetCommInput( void ); void PIOS_IAP_SetRequest1(void); void PIOS_IAP_SetRequest2(void); void PIOS_IAP_ClearRequest(void); -void PIOS_IAP_SetCRC( uint32_t crcval ); +uint16_t PIOS_IAP_ReadBootCount(void); +void PIOS_IAP_WriteBootCount(uint16_t); /**************************************************************************************** * Public Data diff --git a/flight/PiOS/inc/pios_rcvr_priv.h b/flight/PiOS/inc/pios_rcvr_priv.h index 968dc2116..7b41d2764 100644 --- a/flight/PiOS/inc/pios_rcvr_priv.h +++ b/flight/PiOS/inc/pios_rcvr_priv.h @@ -8,7 +8,6 @@ * * @file pios_rcvr_priv.h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) * @brief USART private definitions. * @see The GNU Public License (GPL) Version 3 * diff --git a/flight/PiOS/inc/pios_spi.h b/flight/PiOS/inc/pios_spi.h index 8147bd5d9..2deb8c293 100644 --- a/flight/PiOS/inc/pios_spi.h +++ b/flight/PiOS/inc/pios_spi.h @@ -7,7 +7,6 @@ * * @file pios_spi.h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) * @brief SPI functions header. * @see The GNU Public License (GPL) Version 3 * diff --git a/flight/PiOS/inc/pios_spi_priv.h b/flight/PiOS/inc/pios_spi_priv.h index 266bd03be..68d3629f1 100644 --- a/flight/PiOS/inc/pios_spi_priv.h +++ b/flight/PiOS/inc/pios_spi_priv.h @@ -8,7 +8,6 @@ * * @file pios_spi_priv.h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) * @brief SPI private definitions. * @see The GNU Public License (GPL) Version 3 * diff --git a/flight/PiOS/inc/pios_usart.h b/flight/PiOS/inc/pios_usart.h index 2eb009652..d7bebc18e 100644 --- a/flight/PiOS/inc/pios_usart.h +++ b/flight/PiOS/inc/pios_usart.h @@ -8,7 +8,6 @@ * * @file pios_usart.h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) * @brief USART functions header. * @see The GNU Public License (GPL) Version 3 * diff --git a/flight/PiOS/inc/pios_usart_priv.h b/flight/PiOS/inc/pios_usart_priv.h index edca829aa..defe3bb8a 100644 --- a/flight/PiOS/inc/pios_usart_priv.h +++ b/flight/PiOS/inc/pios_usart_priv.h @@ -8,7 +8,6 @@ * * @file pios_usart_priv.h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) * @brief USART private definitions. * @see The GNU Public License (GPL) Version 3 * diff --git a/flight/PiOS/inc/pios_usb.h b/flight/PiOS/inc/pios_usb.h index f86926e8d..1c6347a0d 100644 --- a/flight/PiOS/inc/pios_usb.h +++ b/flight/PiOS/inc/pios_usb.h @@ -3,13 +3,11 @@ * @addtogroup PIOS PIOS Core hardware abstraction layer * @{ * @addtogroup PIOS_USB USB Functions - * @brief PIOS USB interface code * @{ * * @file pios_usb.h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) - * @brief USB functions header. + * @brief USB HID layer functions header * @see The GNU Public License (GPL) Version 3 * *****************************************************************************/ @@ -32,50 +30,10 @@ #ifndef PIOS_USB_H #define PIOS_USB_H -/* Local defines */ -/* Following settings allow to customise the USB device descriptor */ -#ifndef PIOS_USB_VENDOR_ID -#define PIOS_USB_VENDOR_ID 0x20A0 -#endif - -#ifndef PIOS_USB_VENDOR_STR -#define PIOS_USB_VENDOR_STR "openpilot.org" -#endif - -#ifndef PIOS_USB_PRODUCT_STR -#define PIOS_USB_PRODUCT_STR "OpenPilot" -#endif - -#ifndef PIOS_USB_PRODUCT_ID -#define PIOS_USB_PRODUCT_ID 0x415A -#endif - -#ifndef PIOS_USB_VERSION_ID -#define PIOS_USB_VERSION_ID 0x0102 /* OpenPilot board (01), Running state (02) */ -#endif - -/* Internal defines which are used by PIOS USB HID (don't touch) */ -#define PIOS_USB_EP_NUM 2 - -/* Buffer table base address */ -#define PIOS_USB_BTABLE_ADDRESS 0x000 - -/* EP0 rx/tx buffer base address */ -#define PIOS_USB_ENDP0_RXADDR 0x040 -#define PIOS_USB_ENDP0_TXADDR 0x080 - -/* EP1 Rx/Tx buffer base address for HID driver */ -#define PIOS_USB_ENDP1_TXADDR 0x0C0 -#define PIOS_USB_ENDP1_RXADDR 0x100 - -/* Global Variables */ -extern void (*pEpInt_IN[7]) (void); -extern void (*pEpInt_OUT[7]) (void); - -/* Public Functions */ -extern int32_t PIOS_USB_Init(uint32_t mode); -extern int32_t PIOS_USB_IsInitialized(void); -extern int32_t PIOS_USB_CableConnected(void); +/* Global functions */ +extern int32_t PIOS_USB_Reenumerate(); +extern int32_t PIOS_USB_ChangeConnectionState(uint32_t Connected); +extern bool PIOS_USB_CheckAvailable(uint8_t id); #endif /* PIOS_USB_H */ diff --git a/flight/PiOS/inc/pios_usb_board_data_priv.h b/flight/PiOS/inc/pios_usb_board_data_priv.h new file mode 100644 index 000000000..f4e7f7c05 --- /dev/null +++ b/flight/PiOS/inc/pios_usb_board_data_priv.h @@ -0,0 +1,40 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB_BOARD USB board layer functions + * @{ + * + * @file pios_usb_board_data_priv.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Defines the API to the board-specific USB data setup code + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_USB_BOARD_DATA_PRIV_H +#define PIOS_USB_BOARD_DATA_PRIV_H + +extern int32_t PIOS_USB_BOARD_DATA_Init(void); + +#endif /* PIOS_USB_BOARD_DATA_PRIV_H */ + +/** + * @} + * @} + */ diff --git a/flight/PiOS/inc/pios_usb_cdc_priv.h b/flight/PiOS/inc/pios_usb_cdc_priv.h new file mode 100644 index 000000000..74d6e347d --- /dev/null +++ b/flight/PiOS/inc/pios_usb_cdc_priv.h @@ -0,0 +1,58 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB_COM USB CDC COM layer functions + * @brief Hardware communication layer + * @{ + * + * @file pios_usb_cdc_priv.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief USB COM CDC private definitions. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_USB_CDC_PRIV_H +#define PIOS_USB_CDC_PRIV_H + +#include "usb_core.h" /* RESULT */ + +struct pios_usb_cdc_cfg { + uint8_t ctrl_if; + uint8_t ctrl_tx_ep; + + uint8_t data_if; + uint8_t data_rx_ep; + uint8_t data_tx_ep; +}; + +extern const struct pios_com_driver pios_usb_cdc_com_driver; + +extern int32_t PIOS_USB_CDC_Init(uint32_t * usbcdc_id, const struct pios_usb_cdc_cfg * cfg, uint32_t lower_id); + +extern const uint8_t *PIOS_USB_CDC_GetLineCoding(uint16_t Length); +extern RESULT PIOS_USB_CDC_SetControlLineState(void); +extern RESULT PIOS_USB_CDC_SetLineCoding(void); + +#endif /* PIOS_USB_CDC_PRIV_H */ + +/** + * @} + * @} + */ diff --git a/flight/PiOS/inc/pios_usb_defs.h b/flight/PiOS/inc/pios_usb_defs.h new file mode 100644 index 000000000..2e63a8fa4 --- /dev/null +++ b/flight/PiOS/inc/pios_usb_defs.h @@ -0,0 +1,322 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB_DEFS USB standard types and definitions + * @brief USB standard types and definitions + * @{ + * + * @file pios_usb_defs.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief USB Standard types and definitions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_USB_DEFS_H +#define PIOS_USB_DEFS_H + +#include /* uint*_t */ + +enum usb_desc_types { + USB_DESC_TYPE_DEVICE = 0x01, + USB_DESC_TYPE_CONFIGURATION = 0x02, + USB_DESC_TYPE_STRING = 0x03, + USB_DESC_TYPE_INTERFACE = 0x04, + USB_DESC_TYPE_ENDPOINT = 0x05, + USB_DESC_TYPE_IAD = 0x0B, + USB_DESC_TYPE_HID = 0x21, + USB_DESC_TYPE_REPORT = 0x22, + USB_DESC_TYPE_CLASS_SPECIFIC = 0x24, +} __attribute__((packed)); + +enum usb_interface_class { + USB_INTERFACE_CLASS_CDC = 0x02, + USB_INTERFACE_CLASS_HID = 0x03, + USB_INTERFACE_CLASS_DATA = 0x0A, +} __attribute__((packed)); + +enum usb_cdc_desc_subtypes { + USB_CDC_DESC_SUBTYPE_HEADER = 0x00, + USB_CDC_DESC_SUBTYPE_CALLMGMT = 0x01, + USB_CDC_DESC_SUBTYPE_ABSTRACT_CTRL = 0x02, + USB_CDC_DESC_SUBTYPE_UNION = 0x06, +} __attribute__((packed)); + +enum usb_ep_attr { + USB_EP_ATTR_TT_CONTROL = 0x00, + USB_EP_ATTR_TT_ISOCHRONOUS = 0x01, + USB_EP_ATTR_TT_BULK = 0x02, + USB_EP_ATTR_TT_INTERRUPT = 0x03, +} __attribute__((packed)); + +/* Standard macros to convert from host endian to USB endian (ie. little endian) */ +#if __BIG_ENDIAN__ +#define htousbs(v) ((uint16_t)(\ + ((((v) >> 0) & 0xFF) << 8) | \ + ((((v) >> 8) & 0xFF) << 0))) +#define htousbl(v) ((uint32_t)(\ + ((((v) >> 0) & 0xFF) << 24) | \ + ((((v) >> 8) & 0xFF) << 16) | \ + ((((v) >> 16) & 0xFF) << 8) | \ + ((((v) >> 24) & 0xFF) << 0))) +#else +#define htousbs(v) (v) +#define htousbl(v) (v) +#endif + +#define USB_EP_IN(ep) ((uint8_t) (0x80 | ((ep) & 0xF))) +#define USB_EP_OUT(ep) ((uint8_t) (0x00 | ((ep) & 0xF))) + +#define HID_ITEM_TYPE_MAIN 0x0 +#define HID_ITEM_TYPE_GLOBAL 0x1 +#define HID_ITEM_TYPE_LOCAL 0x2 +#define HID_ITEM_TYPE_RSVD 0x3 + +#define HID_TAG_GLOBAL_USAGE_PAGE 0x0 /* 0b0000 */ +#define HID_TAG_GLOBAL_LOGICAL_MIN 0x1 /* 0b0001 */ +#define HID_TAG_GLOBAL_LOGICAL_MAX 0x2 /* 0b0010 */ +#define HID_TAG_GLOBAL_PHYS_MIN 0x3 /* 0b0011 */ +#define HID_TAG_GLOBAL_PHYS_MAX 0x4 /* 0b0100 */ +#define HID_TAG_GLOBAL_UNIT_EXP 0x5 /* 0b0101 */ +#define HID_TAG_GLOBAL_UNIT 0x6 /* 0b0110 */ +#define HID_TAG_GLOBAL_REPORT_SIZE 0x7 /* 0b0111 */ +#define HID_TAG_GLOBAL_REPORT_ID 0x8 /* 0b1000 */ +#define HID_TAG_GLOBAL_REPORT_CNT 0x9 /* 0b1001 */ +#define HID_TAG_GLOBAL_PUSH 0xA /* 0b1010 */ +#define HID_TAG_GLOBAL_POP 0xB /* 0b1011 */ + +#define HID_TAG_MAIN_INPUT 0x8 /* 0b1000 */ +#define HID_TAG_MAIN_OUTPUT 0x9 /* 0b1001 */ +#define HID_TAG_MAIN_COLLECTION 0xA /* 0b1010 */ +#define HID_TAG_MAIN_FEATURE 0xB /* 0b1011 */ +#define HID_TAG_MAIN_ENDCOLLECTION 0xC /* 0b1100 */ + +#define HID_TAG_LOCAL_USAGE 0x0 /* 0b0000 */ +#define HID_TAG_LOCAL_USAGE_MIN 0x1 /* 0b0001 */ +#define HID_TAG_LOCAL_USAGE_MAX 0x2 /* 0b0010 */ +#define HID_TAG_LOCAL_DESIG_INDEX 0x3 /* 0b0011 */ +#define HID_TAG_LOCAL_DESIG_MIN 0x4 /* 0b0100 */ +#define HID_TAG_LOCAL_DESIG_MAX 0x5 /* 0b0101 */ +/* There is no value defined for 0x6 */ +#define HID_TAG_LOCAL_STRING_INDEX 0x7 /* 0b0111 */ +#define HID_TAG_LOCAL_STRING_MIN 0x8 /* 0b1000 */ +#define HID_TAG_LOCAL_STRING_MAX 0x9 /* 0b1001 */ +#define HID_TAG_LOCAL_DELIMITER 0xA /* 0b1010 */ + +#define HID_TAG_RSVD 0xF /* 0b1111 */ + +#define HID_ITEM_SIZE_0 0 +#define HID_ITEM_SIZE_1 1 +#define HID_ITEM_SIZE_2 2 +#define HID_ITEM_SIZE_4 3 /* Yes, 4 bytes is represented with a size field = 3 */ + +#define HID_SHORT_ITEM(tag,type,size) (\ + (((tag) & 0xF) << 4) | \ + (((type) & 0x3) << 2) | \ + (((size) & 0x3) << 0)) + +/* Long items have a fixed prefix */ +#define HID_LONG_ITEM HID_SHORT_ITEM(HID_TAG_RSVD, HID_ITEM_TYPE_RSVD, HID_ITEM_SIZE_2) + +#define HID_MAIN_ITEM_0(tag) HID_SHORT_ITEM((tag), HID_ITEM_TYPE_MAIN, HID_ITEM_SIZE_0) +#define HID_MAIN_ITEM_1(tag) HID_SHORT_ITEM((tag), HID_ITEM_TYPE_MAIN, HID_ITEM_SIZE_1) +#define HID_MAIN_ITEM_2(tag) HID_SHORT_ITEM((tag), HID_ITEM_TYPE_MAIN, HID_ITEM_SIZE_2) +#define HID_MAIN_ITEM_4(tag) HID_SHORT_ITEM((tag), HID_ITEM_TYPE_MAIN, HID_ITEM_SIZE_4) + +#define HID_GLOBAL_ITEM_0(tag) HID_SHORT_ITEM((tag), HID_ITEM_TYPE_GLOBAL, HID_ITEM_SIZE_0) +#define HID_GLOBAL_ITEM_1(tag) HID_SHORT_ITEM((tag), HID_ITEM_TYPE_GLOBAL, HID_ITEM_SIZE_1) +#define HID_GLOBAL_ITEM_2(tag) HID_SHORT_ITEM((tag), HID_ITEM_TYPE_GLOBAL, HID_ITEM_SIZE_2) +#define HID_GLOBAL_ITEM_4(tag) HID_SHORT_ITEM((tag), HID_ITEM_TYPE_GLOBAL, HID_ITEM_SIZE_4) + +#define HID_LOCAL_ITEM_0(tag) HID_SHORT_ITEM((tag), HID_ITEM_TYPE_LOCAL, HID_ITEM_SIZE_0) +#define HID_LOCAL_ITEM_1(tag) HID_SHORT_ITEM((tag), HID_ITEM_TYPE_LOCAL, HID_ITEM_SIZE_1) +#define HID_LOCAL_ITEM_2(tag) HID_SHORT_ITEM((tag), HID_ITEM_TYPE_LOCAL, HID_ITEM_SIZE_2) +#define HID_LOCAL_ITEM_3(tag) HID_SHORT_ITEM((tag), HID_ITEM_TYPE_LOCAL, HID_ITEM_SIZE_3) + +struct usb_device_desc { + uint8_t bLength; + uint8_t bDescriptorType; + uint16_t bcdUSB; + uint8_t bDeviceClass; + uint8_t bDeviceSubClass; + uint8_t bDeviceProtocol; + uint8_t bMaxPacketSize0; + uint16_t idVendor; + uint16_t idProduct; + uint16_t bcdDevice; + uint8_t iManufacturer; + uint8_t iProduct; + uint8_t iSerialNumber; + uint8_t bNumConfigurations; +} __attribute__((packed)); + +struct usb_configuration_desc { + uint8_t bLength; + uint8_t bDescriptorType; + uint16_t wTotalLength; + uint8_t bNumInterfaces; + uint8_t bConfigurationValue; + uint8_t iConfiguration; + uint8_t bmAttributes; + uint8_t bMaxPower; +} __attribute__((packed)); + +struct usb_interface_association_desc { + uint8_t bLength; + uint8_t bDescriptorType; + uint8_t bFirstInterface; + uint8_t bInterfaceCount; + uint8_t bFunctionClass; + uint8_t bFunctionSubClass; + uint8_t bFunctionProtocol; + uint8_t iInterface; +} __attribute__((packed)); + +struct usb_interface_desc { + uint8_t bLength; + uint8_t bDescriptorType; + uint8_t bInterfaceNumber; + uint8_t bAlternateSetting; + uint8_t bNumEndpoints; + uint8_t bInterfaceClass; + uint8_t bInterfaceSubClass; + uint8_t nInterfaceProtocol; + uint8_t iInterface; +} __attribute__((packed)); + +struct usb_hid_desc { + uint8_t bLength; + uint8_t bDescriptorType; + uint16_t bcdHID; + uint8_t bCountryCode; + uint8_t bNumDescriptors; + uint8_t bClassDescriptorType; + uint16_t wItemLength; +} __attribute__((packed)); + +struct usb_endpoint_desc { + uint8_t bLength; + uint8_t bDescriptorType; + uint8_t bEndpointAddress; + uint8_t bmAttributes; + uint16_t wMaxPacketSize; + uint8_t bInterval; +} __attribute__((packed)); + +struct usb_cdc_header_func_desc { + uint8_t bLength; + uint8_t bDescriptorType; + uint8_t bDescriptorSubType; + uint16_t bcdCDC; +} __attribute__((packed)); + +struct usb_cdc_callmgmt_func_desc { + uint8_t bLength; + uint8_t bDescriptorType; + uint8_t bDescriptorSubType; + uint8_t bmCapabilities; + uint8_t bDataInterface; +} __attribute__((packed)); + +struct usb_cdc_acm_func_desc { + uint8_t bLength; + uint8_t bDescriptorType; + uint8_t bDescriptorSubType; + uint8_t bmCapabilities; +} __attribute__((packed)); + +struct usb_cdc_union_func_desc { + uint8_t bLength; + uint8_t bDescriptorType; + uint8_t bDescriptorSubType; + uint8_t bMasterInterface; + uint8_t bSlaveInterface; +} __attribute__((packed)); + +#define USB_LANGID_ENGLISH_UK 0x0809 + +struct usb_string_langid { + uint8_t bLength; + uint8_t bDescriptorType; + uint16_t bLangID; +} __attribute__((packed)); + +struct usb_cdc_line_coding { + uint32_t dwDTERate; + uint8_t bCharFormat; + uint8_t bParityType; + uint8_t bDataBits; +} __attribute__((packed)); + +enum usb_cdc_line_coding_stop { + USB_CDC_LINE_CODING_STOP_1 = 0, + USB_CDC_LINE_CODING_STOP_1_5 = 1, + USB_CDC_LINE_CODING_STOP_2 = 2, +} __attribute__((packed)); + +enum usb_cdc_line_coding_parity { + USB_CDC_LINE_CODING_PARITY_NONE = 0, + USB_CDC_LINE_CODING_PARITY_ODD = 1, + USB_CDC_LINE_CODING_PARITY_EVEN = 2, + USB_CDC_LINE_CODING_PARITY_MARK = 3, + USB_CDC_LINE_CODING_PARITY_SPACE = 4, +} __attribute__((packed)); + +struct usb_cdc_serial_state_report { + uint8_t bmRequestType; + uint8_t bNotification; + uint16_t wValue; + uint16_t wIndex; + uint16_t wLength; + uint16_t bmUartState; +} __attribute__((packed)); + +enum usb_cdc_notification { + USB_CDC_NOTIFICATION_SERIAL_STATE = 0x20, +} __attribute__((packed)); + +/* + * OpenPilot Specific USB Definitions + */ + +#define USB_VENDOR_ID_OPENPILOT 0x20A0 + +enum usb_product_ids { + USB_PRODUCT_ID_OPENPILOT_MAIN = 0x415A, + USB_PRODUCT_ID_COPTERCONTROL = 0x415B, + USB_PRODUCT_ID_PIPXTREME = 0x415C, +} __attribute__((packed)); + +enum usb_op_board_ids { + USB_OP_BOARD_ID_OPENPILOT_MAIN = 1, + /* Board ID 2 may be unused or AHRS */ + USB_OP_BOARD_ID_PIPXTREME = 3, + USB_OP_BOARD_ID_COPTERCONTROL = 4, +} __attribute__((packed)); + +enum usb_op_board_modes { + USB_OP_BOARD_MODE_BL = 1, + USB_OP_BOARD_MODE_FW = 2, +} __attribute__((packed)); + +#define USB_OP_DEVICE_VER(board_id, board_mode) (\ + ((board_id & 0xFF) << 8) | \ + ((board_mode & 0xFF) << 0)) + +#endif /* PIOS_USB_DEFS_H */ diff --git a/flight/PiOS/inc/pios_usb_desc_hid_cdc_priv.h b/flight/PiOS/inc/pios_usb_desc_hid_cdc_priv.h new file mode 100644 index 000000000..2ae94c74e --- /dev/null +++ b/flight/PiOS/inc/pios_usb_desc_hid_cdc_priv.h @@ -0,0 +1,42 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB_DESC USB descriptor layer functions + * @{ + * + * @file pios_usb_desc_hid_cdc_priv.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Defines the API to set up the HID + CDC USB descriptor config + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_USB_DESC_HID_CDC_PRIV_H +#define PIOS_USB_DESC_HID_CDC_PRIV_H + +#include + +extern int32_t PIOS_USB_DESC_HID_CDC_Init(void); + +#endif /* PIOS_USB_DESC_HID_CDC_PRIV_H */ + +/** + * @} + * @} + */ diff --git a/flight/PiOS/inc/pios_usb_desc_hid_only_priv.h b/flight/PiOS/inc/pios_usb_desc_hid_only_priv.h new file mode 100644 index 000000000..321d15efa --- /dev/null +++ b/flight/PiOS/inc/pios_usb_desc_hid_only_priv.h @@ -0,0 +1,42 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB_DESC USB descriptor layer functions + * @{ + * + * @file pios_usb_desc_hid_only_priv.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Defines the API to set up the HID-only USB descriptor config + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_USB_DESC_HID_ONLY_PRIV_H +#define PIOS_USB_DESC_HID_ONLY_PRIV_H + +#include + +extern int32_t PIOS_USB_DESC_HID_ONLY_Init(void); + +#endif /* PIOS_USB_DESC_HID_ONLY_PRIV_H */ + +/** + * @} + * @} + */ diff --git a/flight/PiOS/inc/pios_usb_hid.h b/flight/PiOS/inc/pios_usb_hid.h index 67067ba72..7a7409631 100644 --- a/flight/PiOS/inc/pios_usb_hid.h +++ b/flight/PiOS/inc/pios_usb_hid.h @@ -7,7 +7,6 @@ * * @file pios_usb_hid.h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) * @brief USB HID layer functions header * @see The GNU Public License (GPL) Version 3 * @@ -31,24 +30,10 @@ #ifndef PIOS_USB_HID_H #define PIOS_USB_HID_H -/* Global Definitions */ -#define PIOS_USB_HID_SIZ_REPORT_DESC 32 -#define PIOS_USB_HID_REPORT_DESCRIPTOR 0x22 -#define PIOS_USB_HID_HID_DESCRIPTOR_TYPE 0x21 -#define PIOS_USB_HID_OFF_HID_DESC 0x12 -#define PIOS_USB_HID_SIZ_HID_DESC 0x09 - -#define PIOS_USB_HID_DATA_LENGTH 62 - /* Global functions */ extern int32_t PIOS_USB_HID_Reenumerate(); extern int32_t PIOS_USB_HID_ChangeConnectionState(uint32_t Connected); -extern int32_t PIOS_USB_HID_CheckAvailable(uint8_t id); - -extern int32_t PIOS_USB_HID_CB_Data_Setup(uint8_t RequestNo); -extern int32_t PIOS_USB_HID_CB_NoData_Setup(uint8_t RequestNo); -extern void PIOS_USB_HID_EP1_IN_Callback(void); -extern void PIOS_USB_HID_EP1_OUT_Callback(void); +extern bool PIOS_USB_HID_CheckAvailable(uint8_t id); #endif /* PIOS_USB_HID_H */ diff --git a/flight/PiOS/inc/pios_usb_hid_desc.h b/flight/PiOS/inc/pios_usb_hid_desc.h deleted file mode 100644 index ba9af390b..000000000 --- a/flight/PiOS/inc/pios_usb_hid_desc.h +++ /dev/null @@ -1,56 +0,0 @@ -/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** -* File Name : usb_desc.h -* Author : MCD Application Team -* Version : V3.2.1 -* Date : 07/05/2010 -* Description : Descriptor Header for Custom HID Demo -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __USB_DESC_H -#define __USB_DESC_H - -/* Includes ------------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ -/* Exported define -----------------------------------------------------------*/ -#define USB_DEVICE_DESCRIPTOR_TYPE 0x01 -#define USB_CONFIGURATION_DESCRIPTOR_TYPE 0x02 -#define USB_STRING_DESCRIPTOR_TYPE 0x03 -#define USB_INTERFACE_DESCRIPTOR_TYPE 0x04 -#define USB_ENDPOINT_DESCRIPTOR_TYPE 0x05 - -#define HID_DESCRIPTOR_TYPE 0x21 -#define PIOS_HID_SIZ_HID_DESC 0x09 -#define PIOS_HID_OFF_HID_DESC 0x12 - -#define PIOS_HID_SIZ_DEVICE_DESC 18 -#define PIOS_HID_SIZ_CONFIG_DESC 41 -#define PIOS_HID_SIZ_REPORT_DESC 36 -#define PIOS_HID_SIZ_STRING_LANGID 4 -#define PIOS_HID_SIZ_STRING_VENDOR 28 -#define PIOS_HID_SIZ_STRING_PRODUCT 20 -#define PIOS_HID_SIZ_STRING_SERIAL 52 /* 96 bits, 12 bytes, 24 characters, 48 in unicode */ - -#define STANDARD_ENDPOINT_DESC_SIZE 0x09 - -/* Exported functions ------------------------------------------------------- */ -extern const uint8_t PIOS_HID_DeviceDescriptor[PIOS_HID_SIZ_DEVICE_DESC]; -extern const uint8_t PIOS_HID_ConfigDescriptor[PIOS_HID_SIZ_CONFIG_DESC]; -extern const uint8_t PIOS_HID_ReportDescriptor[PIOS_HID_SIZ_REPORT_DESC]; -extern const uint8_t PIOS_HID_StringLangID[PIOS_HID_SIZ_STRING_LANGID]; -extern const uint8_t PIOS_HID_StringVendor[PIOS_HID_SIZ_STRING_VENDOR]; -extern const uint8_t PIOS_HID_StringProduct[PIOS_HID_SIZ_STRING_PRODUCT]; -extern uint8_t PIOS_HID_StringSerial[PIOS_HID_SIZ_STRING_SERIAL]; - -#endif /* __USB_DESC_H */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/inc/pios_usb_hid_priv.h b/flight/PiOS/inc/pios_usb_hid_priv.h index 5a8652762..ac638cd54 100644 --- a/flight/PiOS/inc/pios_usb_hid_priv.h +++ b/flight/PiOS/inc/pios_usb_hid_priv.h @@ -1,14 +1,14 @@ - /** +/** ****************************************************************************** * @addtogroup PIOS PIOS Core hardware abstraction layer * @{ - * @addtogroup PIOS_USB_HID USB_HID Functions - * @brief PIOS interface for USB_HID port + * @addtogroup PIOS_USB_COM USB HID COM layer functions + * @brief Hardware communication layer * @{ * * @file pios_usb_hid_priv.h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief USB_HID private definitions. + * @brief USB COM HID private definitions. * @see The GNU Public License (GPL) Version 3 * *****************************************************************************/ @@ -31,14 +31,17 @@ #ifndef PIOS_USB_HID_PRIV_H #define PIOS_USB_HID_PRIV_H -#include -#include +#include "usb_core.h" /* RESULT */ struct pios_usb_hid_cfg { - struct stm32_irq irq; + uint8_t data_if; + uint8_t data_rx_ep; + uint8_t data_tx_ep; }; -extern int32_t PIOS_USB_HID_Init(uint32_t * usb_hid_id, const struct pios_usb_hid_cfg * cfg); +extern const struct pios_com_driver pios_usb_hid_com_driver; + +extern int32_t PIOS_USB_HID_Init(uint32_t * usbhid_id, const struct pios_usb_hid_cfg * cfg, uint32_t lower_id); #endif /* PIOS_USB_HID_PRIV_H */ @@ -46,4 +49,3 @@ extern int32_t PIOS_USB_HID_Init(uint32_t * usb_hid_id, const struct pios_usb_hi * @} * @} */ - diff --git a/flight/PiOS/inc/pios_usb_hid_prop.h b/flight/PiOS/inc/pios_usb_hid_prop.h deleted file mode 100644 index e721fc93e..000000000 --- a/flight/PiOS/inc/pios_usb_hid_prop.h +++ /dev/null @@ -1,68 +0,0 @@ -/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** -* File Name : usb_prop.h -* Author : MCD Application Team -* Version : V3.2.1 -* Date : 07/05/2010 -* Description : All processings related to Custom HID demo -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __USB_PROP_H -#define __USB_PROP_H - -/* Includes ------------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -typedef enum _HID_REQUESTS { - GET_REPORT = 1, - GET_IDLE, - GET_PROTOCOL, - - SET_REPORT = 9, - SET_IDLE, - SET_PROTOCOL -} HID_REQUESTS; - -/* Exported constants --------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions ------------------------------------------------------- */ -void PIOS_HID_init(void); -void PIOS_HID_Reset(void); -void PIOS_HID_SetConfiguration(void); -void PIOS_HID_SetDeviceAddress(void); -void PIOS_HID_Status_In(void); -void PIOS_HID_Status_Out(void); -RESULT PIOS_HID_Data_Setup(uint8_t); -RESULT PIOS_HID_NoData_Setup(uint8_t); -RESULT PIOS_HID_Get_Interface_Setting(uint8_t Interface, uint8_t AlternateSetting); -uint8_t *PIOS_HID_GetDeviceDescriptor(uint16_t); -uint8_t *PIOS_HID_GetConfigDescriptor(uint16_t); -uint8_t *PIOS_HID_GetStringDescriptor(uint16_t); -RESULT PIOS_HID_SetProtocol(void); -uint8_t *PIOS_HID_GetProtocolValue(uint16_t Length); -RESULT PIOS_HID_SetProtocol(void); -uint8_t *PIOS_HID_GetReportDescriptor(uint16_t Length); -uint8_t *PIOS_HID_GetHIDDescriptor(uint16_t Length); - -/* Exported define -----------------------------------------------------------*/ -#define PIOS_HID_GetConfiguration NOP_Process -//#define PIOS_HID_SetConfiguration NOP_Process -#define PIOS_HID_GetInterface NOP_Process -#define PIOS_HID_SetInterface NOP_Process -#define PIOS_HID_GetStatus NOP_Process -#define PIOS_HID_ClearFeature NOP_Process -#define PIOS_HID_SetEndPointFeature NOP_Process -#define PIOS_HID_SetDeviceFeature NOP_Process -//#define PIOS_HID_SetDeviceAddress NOP_Process - -#define REPORT_DESCRIPTOR 0x22 - -#endif /* __USB_PROP_H */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PiOS/inc/pios_usb_priv.h b/flight/PiOS/inc/pios_usb_priv.h new file mode 100644 index 000000000..dd3f949ee --- /dev/null +++ b/flight/PiOS/inc/pios_usb_priv.h @@ -0,0 +1,49 @@ + /** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB USB Setup Functions + * @brief PIOS interface for USB device driver + * @{ + * + * @file pios_usb_priv.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief USB private definitions. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_USB_PRIV_H +#define PIOS_USB_PRIV_H + +#include +#include + +struct pios_usb_cfg { + struct stm32_irq irq; +}; + +extern int32_t PIOS_USB_Init(uint32_t * usb_id, const struct pios_usb_cfg * cfg); + +#endif /* PIOS_USB_PRIV_H */ + +/** + * @} + * @} + */ + diff --git a/flight/PiOS/inc/pios_usbhook.h b/flight/PiOS/inc/pios_usbhook.h new file mode 100644 index 000000000..f005a6fa1 --- /dev/null +++ b/flight/PiOS/inc/pios_usbhook.h @@ -0,0 +1,64 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USBHOOK USB glue code + * @brief Glue between PiOS and STM32 libs + * @{ + * + * @file pios_usbhook.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief APIs for PIOS_USBHOOK layer + * @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_USBHOOK_H +#define PIOS_USBHOOK_H + +typedef enum _HID_REQUESTS { + GET_REPORT = 1, + GET_IDLE, + GET_PROTOCOL, + + SET_REPORT = 9, + SET_IDLE, + SET_PROTOCOL +} HID_REQUESTS; + +typedef enum CDC_REQUESTS { + SET_LINE_CODING = 0x20, + GET_LINE_CODING = 0x21, + SET_CONTROL_LINE_STATE = 0x23, +} CDC_REQUESTS; + +enum usb_string_desc { + USB_STRING_DESC_LANG = 0, + USB_STRING_DESC_VENDOR = 1, + USB_STRING_DESC_PRODUCT = 2, + USB_STRING_DESC_SERIAL = 3, +} __attribute__((packed)); + +extern void PIOS_USBHOOK_RegisterDevice(const uint8_t * desc, uint16_t desc_size); +extern void PIOS_USBHOOK_RegisterConfig(uint8_t config_id, const uint8_t * desc, uint16_t desc_size); +extern void PIOS_USBHOOK_RegisterString(enum usb_string_desc string_id, const uint8_t * desc, uint16_t desc_size); +extern void PIOS_USBHOOK_RegisterHidInterface(const uint8_t * desc, uint16_t desc_size); +extern void PIOS_USBHOOK_RegisterHidReport(const uint8_t * desc, uint16_t desc_size); + +#endif /* PIOS_USBHOOK_H */ + diff --git a/flight/PiOS/inc/usb_conf.h b/flight/PiOS/inc/usb_conf.h index eb2198a0b..f174eaf62 100644 --- a/flight/PiOS/inc/usb_conf.h +++ b/flight/PiOS/inc/usb_conf.h @@ -23,11 +23,6 @@ /* Exported macro ------------------------------------------------------------*/ /* Exported functions ------------------------------------------------------- */ /* External variables --------------------------------------------------------*/ -/*-------------------------------------------------------------*/ -/* EP_NUM */ -/* defines how many endpoints are used by the device */ -/*-------------------------------------------------------------*/ -#define EP_NUM (2) #ifndef STM32F10X_CL /*-------------------------------------------------------------*/ @@ -39,13 +34,23 @@ /* EP0 */ /* rx/tx buffer base address */ -#define ENDP0_RXADDR (0x18) -#define ENDP0_TXADDR (0x58) +#define ENDP0_RXADDR (0x20) +#define ENDP0_TXADDR (0x40) /* EP1 */ -/* tx buffer base address */ -#define ENDP1_TXADDR (0x100) -#define ENDP1_RXADDR (0x124) +/* rx/tx buffer base address */ +#define ENDP1_TXADDR (0x60) +#define ENDP1_RXADDR (0x80) + +/* EP2 */ +/* rx/tx buffer base address */ +#define ENDP2_TXADDR (0x100) +#define ENDP2_RXADDR (0x140) + +/* EP3 */ +/* rx/tx buffer base address */ +#define ENDP3_TXADDR (0x180) +#define ENDP3_RXADDR (0x1C0) /*-------------------------------------------------------------*/ /* ------------------- ISTR events -------------------------*/ @@ -171,7 +176,7 @@ #define EP6_IN_Callback NOP_Process #define EP7_IN_Callback NOP_Process -//#define EP1_OUT_Callback NOP_Process +#define EP1_OUT_Callback NOP_Process #define EP2_OUT_Callback NOP_Process #define EP3_OUT_Callback NOP_Process #define EP4_OUT_Callback NOP_Process diff --git a/flight/PiOS/pios.h b/flight/PiOS/pios.h index bc06f73ca..88ed15f09 100644 --- a/flight/PiOS/pios.h +++ b/flight/PiOS/pios.h @@ -131,7 +131,9 @@ #if defined(PIOS_INCLUDE_MS5611) #include #endif +#if defined(PIOS_INCLUDE_IAP) #include +#endif #if defined(PIOS_INCLUDE_ADXL345) #include @@ -151,6 +153,7 @@ #if defined(PIOS_INCLUDE_USB) /* USB Libs */ #include +#include #endif #include diff --git a/flight/PipXtreme/Makefile b/flight/PipXtreme/Makefile index 8a939d411..c4bc900ca 100644 --- a/flight/PipXtreme/Makefile +++ b/flight/PipXtreme/Makefile @@ -97,10 +97,6 @@ SRC += $(HOME_DIR)/gpio_in.c SRC += $(HOME_DIR)/stopwatch.c SRC += $(HOME_DIR)/watchdog.c SRC += $(FLIGHTLIB)/fifo_buffer.c -ifeq ($(USE_USB), YES) - SRC += $(HOME_DIR)/pios_usb_hid_desc.c -endif - ## PIOS Hardware (STM32F10x) SRC += $(PIOSSTM32F10X)/pios_sys.c @@ -115,12 +111,13 @@ SRC += $(PIOSSTM32F10X)/pios_ppm.c # PIOS USB related files (seperated to make code maintenance more easy) ifeq ($(USE_USB), YES) + SRC += $(PIOSSTM32F10X)/pios_usb.c + SRC += $(PIOSSTM32F10X)/pios_usbhook.c SRC += $(PIOSSTM32F10X)/pios_usb_hid.c - #SRC += $(PIOSSTM32F10X)/pios_usb_hid_desc.c - #SRC += $(PIOSSTM32F10X)/pios_usb_hid_endp.c SRC += $(PIOSSTM32F10X)/pios_usb_hid_istr.c - SRC += $(PIOSSTM32F10X)/pios_usb_hid_prop.c SRC += $(PIOSSTM32F10X)/pios_usb_hid_pwr.c + SRC += $(HOME_DIR)/pios_usb_board_data.c + SRC += $(PIOSCOMMON)/pios_usb_desc_hid_only.c endif ## PIOS Hardware (Common) diff --git a/flight/PipXtreme/api_config.c b/flight/PipXtreme/api_config.c index 2cecfc65e..5aa9fc6c0 100644 --- a/flight/PipXtreme/api_config.c +++ b/flight/PipXtreme/api_config.c @@ -35,6 +35,7 @@ #include "saved_settings.h" #include "crc.h" #include "main.h" +#include "pios_usb.h" /* PIOS_USB_* */ #if defined(PIOS_COM_DEBUG) // #define APICONFIG_DEBUG @@ -773,8 +774,8 @@ void apiconfig_process(void) // decide which comm-port we are using (usart or usb) apiconfig_usb_comms = false; // TRUE if we are using the usb port for comms. apiconfig_comm_port = PIOS_COM_SERIAL; // default to using the usart comm-port - #if defined(PIOS_INCLUDE_USB_HID) - if (PIOS_USB_HID_CheckAvailable(0)) + #if defined(PIOS_INCLUDE_USB) + if (PIOS_USB_CheckAvailable(0)) { // USB comms is up, use the USB comm-port instead of the USART comm-port apiconfig_usb_comms = true; apiconfig_comm_port = PIOS_COM_TELEM_USB; @@ -791,13 +792,8 @@ void apiconfig_process(void) else if (apiconfig_usb_comms) { // we're using the USB for comms - keep the USART rx buffer empty - int32_t bytes = PIOS_COM_ReceiveBufferUsed(PIOS_COM_SERIAL); - while (bytes > 0) - { - uint8_t c; - PIOS_COM_ReceiveBuffer(PIOS_COM_SERIAL, &c, 1, 0); - bytes--; - } + uint8_t c; + while (PIOS_COM_ReceiveBuffer(PIOS_COM_SERIAL, &c, 1, 0) > 0); } apiconfig_previous_com_port = apiconfig_comm_port; // remember the current comm-port we are using @@ -807,20 +803,9 @@ void apiconfig_process(void) // fetch the data received via the comm-port // get the number of data bytes received down the comm-port - int32_t com_num = PIOS_COM_ReceiveBufferUsed(apiconfig_comm_port); + uint16_t buf_avail = sizeof(apiconfig_rx_buffer) - apiconfig_rx_buffer_wr; - // limit number of bytes we will get to how much space we have in our RX buffer - if (com_num > sizeof(apiconfig_rx_buffer) - apiconfig_rx_buffer_wr) - com_num = sizeof(apiconfig_rx_buffer) - apiconfig_rx_buffer_wr; - - - while (com_num > 0) - { // fetch a byte from the comm-port RX buffer and save it into our RX buffer - uint8_t c; - PIOS_COM_ReceiveBuffer(apiconfig_comm_port, &c, 1, 0); - apiconfig_rx_buffer[apiconfig_rx_buffer_wr++] = c; - com_num--; - } + PIOS_COM_ReceiveBuffer(apiconfig_comm_port, &(apiconfig_rx_buffer[apiconfig_rx_buffer_wr]), buf_avail, 0); apiconfig_processTx(); apiconfig_processRx(); diff --git a/flight/PipXtreme/inc/pios_config.h b/flight/PipXtreme/inc/pios_config.h index 7fac02079..46728b2cb 100644 --- a/flight/PipXtreme/inc/pios_config.h +++ b/flight/PipXtreme/inc/pios_config.h @@ -39,6 +39,7 @@ #define PIOS_INCLUDE_COM #define PIOS_INCLUDE_GPIO #define PIOS_INCLUDE_EXTI +#define PIOS_INCLUDE_USB #define PIOS_INCLUDE_USB_HID #endif /* PIOS_CONFIG_H */ diff --git a/flight/PipXtreme/inc/pios_usb.h b/flight/PipXtreme/inc/pios_usb.h deleted file mode 100644 index bab436469..000000000 --- a/flight/PipXtreme/inc/pios_usb.h +++ /dev/null @@ -1,79 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_USB USB Functions - * @brief PIOS USB interface code - * @{ - * - * @file pios_usb.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) - * @brief USB 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_USB_H -#define PIOS_USB_H - -/* Local defines */ -/* Following settings allow to customise the USB device descriptor */ -#ifndef PIOS_USB_VENDOR_ID -#define PIOS_USB_VENDOR_ID 0x20A0 -#endif - - -#ifndef PIOS_USB_PRODUCT_ID -#define PIOS_USB_PRODUCT_ID 0x415C // PipXtreme PID -#endif - -#ifndef PIOS_USB_VERSION_ID -#define PIOS_USB_VERSION_ID 0x0302 // PipXtreme, board revision 1, Running state (02) -#endif - -/* Internal defines which are used by PIOS USB HID (don't touch) */ -#define PIOS_USB_EP_NUM 2 - -/* Buffer table base address */ -#define PIOS_USB_BTABLE_ADDRESS 0x000 - -/* EP0 rx/tx buffer base address */ -#define PIOS_USB_ENDP0_RXADDR 0x040 -#define PIOS_USB_ENDP0_TXADDR 0x080 - -/* EP1 Rx/Tx buffer base address for HID driver */ -#define PIOS_USB_ENDP1_TXADDR 0x0C0 -#define PIOS_USB_ENDP1_RXADDR 0x100 - - -/* Global Variables */ -extern void (*pEpInt_IN[7])(void); -extern void (*pEpInt_OUT[7])(void); - -/* Public Functions */ -extern int32_t PIOS_USB_Init(uint32_t mode); -extern int32_t PIOS_USB_IsInitialized(void); -extern int32_t PIOS_USB_CableConnected(void); - -#endif /* PIOS_USB_H */ - -/** - * @} - * @} - */ diff --git a/flight/PipXtreme/inc/pios_usb_board_data.h b/flight/PipXtreme/inc/pios_usb_board_data.h new file mode 100644 index 000000000..d4f4daf0a --- /dev/null +++ b/flight/PipXtreme/inc/pios_usb_board_data.h @@ -0,0 +1,43 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB_BOARD Board specific USB definitions + * @brief Board specific USB definitions + * @{ + * + * @file pios_usb_board_data.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Board specific USB definitions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_USB_BOARD_DATA_H +#define PIOS_USB_BOARD_DATA_H + +#define PIOS_USB_BOARD_HID_DATA_LENGTH 64 + +#define PIOS_USB_BOARD_EP_NUM 2 + +#include "pios_usb_defs.h" /* struct usb_* */ + +#define PIOS_USB_BOARD_PRODUCT_ID USB_PRODUCT_ID_PIPXTREME +#define PIOS_USB_BOARD_DEVICE_VER USB_OP_DEVICE_VER(USB_OP_BOARD_ID_PIPXTREME, USB_OP_BOARD_MODE_FW) + +#endif /* PIOS_USB_BOARD_DATA_H */ diff --git a/flight/PipXtreme/inc/pios_usb_hid_desc.h b/flight/PipXtreme/inc/pios_usb_hid_desc.h deleted file mode 100644 index 4810c1274..000000000 --- a/flight/PipXtreme/inc/pios_usb_hid_desc.h +++ /dev/null @@ -1,56 +0,0 @@ -/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** -* File Name : usb_desc.h -* Author : MCD Application Team -* Version : V3.2.1 -* Date : 07/05/2010 -* Description : Descriptor Header for Custom HID Demo -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __USB_DESC_H -#define __USB_DESC_H - -/* Includes ------------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ -/* Exported define -----------------------------------------------------------*/ -#define USB_DEVICE_DESCRIPTOR_TYPE 0x01 -#define USB_CONFIGURATION_DESCRIPTOR_TYPE 0x02 -#define USB_STRING_DESCRIPTOR_TYPE 0x03 -#define USB_INTERFACE_DESCRIPTOR_TYPE 0x04 -#define USB_ENDPOINT_DESCRIPTOR_TYPE 0x05 - -#define HID_DESCRIPTOR_TYPE 0x21 -#define PIOS_HID_SIZ_HID_DESC 0x09 -#define PIOS_HID_OFF_HID_DESC 0x12 - -#define PIOS_HID_SIZ_DEVICE_DESC 18 -#define PIOS_HID_SIZ_CONFIG_DESC 41 -#define PIOS_HID_SIZ_REPORT_DESC 36 -#define PIOS_HID_SIZ_STRING_LANGID 4 -#define PIOS_HID_SIZ_STRING_VENDOR 28 -#define PIOS_HID_SIZ_STRING_PRODUCT 20 -#define PIOS_HID_SIZ_STRING_SERIAL 52 /* 96 bits, 12 bytes, 24 characters, 48 in unicode */ - -#define STANDARD_ENDPOINT_DESC_SIZE 0x09 - -/* Exported functions ------------------------------------------------------- */ -extern const uint8_t PIOS_HID_DeviceDescriptor[PIOS_HID_SIZ_DEVICE_DESC]; -extern const uint8_t PIOS_HID_ConfigDescriptor[PIOS_HID_SIZ_CONFIG_DESC]; -extern const uint8_t PIOS_HID_ReportDescriptor[PIOS_HID_SIZ_REPORT_DESC]; -extern const uint8_t PIOS_HID_StringLangID[PIOS_HID_SIZ_STRING_LANGID]; -extern const uint8_t PIOS_HID_StringVendor[PIOS_HID_SIZ_STRING_VENDOR]; -extern const uint8_t PIOS_HID_StringProduct[PIOS_HID_SIZ_STRING_PRODUCT]; -extern uint8_t PIOS_HID_StringSerial[PIOS_HID_SIZ_STRING_SERIAL]; - -#endif /* __USB_DESC_H */ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ diff --git a/flight/PipXtreme/inc/usb_conf.h b/flight/PipXtreme/inc/usb_conf.h deleted file mode 100644 index 913060c7f..000000000 --- a/flight/PipXtreme/inc/usb_conf.h +++ /dev/null @@ -1,186 +0,0 @@ -/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** -* File Name : usb_conf.h -* Author : MCD Application Team -* Version : V3.2.1 -* Date : 07/05/2010 -* Description : Custom HID demo configuration file -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __USB_CONF_H -#define __USB_CONF_H - -/* Includes ------------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions ------------------------------------------------------- */ -/* External variables --------------------------------------------------------*/ -/*-------------------------------------------------------------*/ -/* EP_NUM */ -/* defines how many endpoints are used by the device */ -/*-------------------------------------------------------------*/ -#define EP_NUM (2) - -#ifndef STM32F10X_CL -/*-------------------------------------------------------------*/ -/* -------------- Buffer Description Table -----------------*/ -/*-------------------------------------------------------------*/ -/* buffer table base address */ -/* buffer table base address */ -#define BTABLE_ADDRESS (0x00) - -/* EP0 */ -/* rx/tx buffer base address */ -#define ENDP0_RXADDR (0x18) -#define ENDP0_TXADDR (0x58) - -/* EP1 */ -/* tx buffer base address */ -#define ENDP1_TXADDR (0x100) -#define ENDP1_RXADDR (0x124) - -/*-------------------------------------------------------------*/ -/* ------------------- ISTR events -------------------------*/ -/*-------------------------------------------------------------*/ -/* IMR_MSK */ -/* mask defining which events has to be handled */ -/* by the device application software */ -#define IMR_MSK (CNTR_CTRM | CNTR_WKUPM | CNTR_SUSPM | CNTR_ERRM | CNTR_SOFM \ - | CNTR_ESOFM | CNTR_RESETM ) -#endif /* STM32F10X_CL */ - -#ifdef STM32F10X_CL - -/******************************************************************************* -* FIFO Size Configuration -* -* (i) Dedicated data FIFO SPRAM of 1.25 Kbytes = 1280 bytes = 320 32-bits words -* available for the endpoints IN and OUT. -* Device mode features: -* -1 bidirectional CTRL EP 0 -* -3 IN EPs to support any kind of Bulk, Interrupt or Isochronous transfer -* -3 OUT EPs to support any kind of Bulk, Interrupt or Isochronous transfer -* -* ii) Receive data FIFO size = RAM for setup packets + -* OUT endpoint control information + -* data OUT packets + miscellaneous -* Space = ONE 32-bits words -* --> RAM for setup packets = 4 * n + 6 space -* (n is the nbr of CTRL EPs the device core supports) -* --> OUT EP CTRL info = 1 space -* (one space for status information written to the FIFO along with each -* received packet) -* --> data OUT packets = (Largest Packet Size / 4) + 1 spaces -* (MINIMUM to receive packets) -* --> OR data OUT packets = at least 2*(Largest Packet Size / 4) + 1 spaces -* (if high-bandwidth EP is enabled or multiple isochronous EPs) -* --> miscellaneous = 1 space per OUT EP -* (one space for transfer complete status information also pushed to the -* FIFO with each endpoint's last packet) -* -* (iii)MINIMUM RAM space required for each IN EP Tx FIFO = MAX packet size for -* that particular IN EP. More space allocated in the IN EP Tx FIFO results -* in a better performance on the USB and can hide latencies on the AHB. -* -* (iv) TXn min size = 16 words. (n : Transmit FIFO index) -* (v) When a TxFIFO is not used, the Configuration should be as follows: -* case 1 : n > m and Txn is not used (n,m : Transmit FIFO indexes) -* --> Txm can use the space allocated for Txn. -* case2 : n < m and Txn is not used (n,m : Transmit FIFO indexes) -* --> Txn should be configured with the minimum space of 16 words -* (vi) The FIFO is used optimally when used TxFIFOs are allocated in the top -* of the FIFO.Ex: use EP1 and EP2 as IN instead of EP1 and EP3 as IN ones. -*******************************************************************************/ - -#define RX_FIFO_SIZE 128 -#define TX0_FIFO_SIZE 64 -#define TX1_FIFO_SIZE 64 -#define TX2_FIFO_SIZE 16 -#define TX3_FIFO_SIZE 16 - -/* OTGD-FS-DEVICE IP interrupts Enable definitions */ -/* Uncomment the define to enable the selected interrupt */ -//#define INTR_MODEMISMATCH -#define INTR_SOFINTR -#define INTR_RXSTSQLVL /* Mandatory */ -//#define INTR_NPTXFEMPTY -//#define INTR_GINNAKEFF -//#define INTR_GOUTNAKEFF -//#define INTR_ERLYSUSPEND -#define INTR_USBSUSPEND /* Mandatory */ -#define INTR_USBRESET /* Mandatory */ -#define INTR_ENUMDONE /* Mandatory */ -//#define INTR_ISOOUTDROP -//#define INTR_EOPFRAME -//#define INTR_EPMISMATCH -#define INTR_INEPINTR /* Mandatory */ -#define INTR_OUTEPINTR /* Mandatory */ -//#define INTR_INCOMPLISOIN -//#define INTR_INCOMPLISOOUT -#define INTR_WKUPINTR /* Mandatory */ - -/* OTGD-FS-DEVICE IP interrupts subroutines */ -/* Comment the define to enable the selected interrupt subroutine and replace it - by user code */ -#define INTR_MODEMISMATCH_Callback NOP_Process -#define INTR_SOFINTR_Callback NOP_Process -#define INTR_RXSTSQLVL_Callback NOP_Process -#define INTR_NPTXFEMPTY_Callback NOP_Process -#define INTR_NPTXFEMPTY_Callback NOP_Process -#define INTR_GINNAKEFF_Callback NOP_Process -#define INTR_GOUTNAKEFF_Callback NOP_Process -#define INTR_ERLYSUSPEND_Callback NOP_Process -#define INTR_USBSUSPEND_Callback NOP_Process -#define INTR_USBRESET_Callback NOP_Process -#define INTR_ENUMDONE_Callback NOP_Process -#define INTR_ISOOUTDROP_Callback NOP_Process -#define INTR_EOPFRAME_Callback NOP_Process -#define INTR_EPMISMATCH_Callback NOP_Process -#define INTR_INEPINTR_Callback NOP_Process -#define INTR_OUTEPINTR_Callback NOP_Process -#define INTR_INCOMPLISOIN_Callback NOP_Process -#define INTR_INCOMPLISOOUT_Callback NOP_Process -#define INTR_WKUPINTR_Callback NOP_Process - -/* Isochronous data update */ -#define INTR_RXSTSQLVL_ISODU_Callback NOP_Process - -/* Isochronous transfer parameters */ -/* Size of a single Isochronous buffer (size of a single transfer) */ -#define ISOC_BUFFER_SZE 1 -/* Number of sub-buffers (number of single buffers/transfers), should be even */ -#define NUM_SUB_BUFFERS 2 - -#endif /* STM32F10X_CL */ - - -/* CTR service routines */ -/* associated to defined endpoints */ -#define EP1_IN_Callback NOP_Process -#define EP2_IN_Callback NOP_Process -#define EP3_IN_Callback NOP_Process -#define EP4_IN_Callback NOP_Process -#define EP5_IN_Callback NOP_Process -#define EP6_IN_Callback NOP_Process -#define EP7_IN_Callback NOP_Process - -//#define EP1_OUT_Callback NOP_Process -#define EP2_OUT_Callback NOP_Process -#define EP3_OUT_Callback NOP_Process -#define EP4_OUT_Callback NOP_Process -#define EP5_OUT_Callback NOP_Process -#define EP6_OUT_Callback NOP_Process -#define EP7_OUT_Callback NOP_Process - -#endif /*__USB_CONF_H*/ - -/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/ - diff --git a/flight/PipXtreme/pios_board.c b/flight/PipXtreme/pios_board.c index 0a69808ad..ab6bcffef 100644 --- a/flight/PipXtreme/pios_board.c +++ b/flight/PipXtreme/pios_board.c @@ -311,10 +311,10 @@ static uint8_t pios_com_serial_tx_buffer[PIOS_COM_SERIAL_TX_BUF_LEN]; // *********************************************************************************** -#if defined(PIOS_INCLUDE_USB_HID) -#include "pios_usb_hid_priv.h" +#if defined(PIOS_INCLUDE_USB) +#include "pios_usb_priv.h" -static const struct pios_usb_hid_cfg pios_usb_hid_main_cfg = { +static const struct pios_usb_cfg pios_usb_main_cfg = { .irq = { .init = { .NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn, @@ -324,9 +324,22 @@ static const struct pios_usb_hid_cfg pios_usb_hid_main_cfg = { }, }, }; -#endif /* PIOS_INCLUDE_USB_HID */ -extern const struct pios_com_driver pios_usb_com_driver; +#include "pios_usb_board_data_priv.h" +#include "pios_usb_desc_hid_only_priv.h" + +#endif /* PIOS_INCLUDE_USB */ + +#if defined(PIOS_INCLUDE_USB_HID) +#include + +const struct pios_usb_hid_cfg pios_usb_hid_cfg = { + .data_if = 0, + .data_rx_ep = 1, + .data_tx_ep = 1, +}; + +#endif /* PIOS_INCLUDE_USB_HID */ uint32_t pios_com_serial_id; uint32_t pios_com_telem_usb_id; @@ -359,16 +372,29 @@ void PIOS_Board_Init(void) { PIOS_DEBUG_Assert(0); } -#if defined(PIOS_INCLUDE_USB_HID) +#if defined(PIOS_INCLUDE_USB) + /* Initialize board specific USB data */ + PIOS_USB_BOARD_DATA_Init(); + + if (PIOS_USB_DESC_HID_ONLY_Init()) { + PIOS_Assert(0); + } + + uint32_t pios_usb_id; + PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg); + +#if defined(PIOS_INCLUDE_USB_HID) && defined(PIOS_INCLUDE_COM) uint32_t pios_usb_hid_id; - PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_main_cfg); -#if defined(PIOS_INCLUDE_COM) - if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_com_driver, pios_usb_hid_id, + if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) { + PIOS_Assert(0); + } + if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id, pios_com_telem_usb_rx_buffer, sizeof(pios_com_telem_usb_rx_buffer), pios_com_telem_usb_tx_buffer, sizeof(pios_com_telem_usb_tx_buffer))) { PIOS_Assert(0); } -#endif /* PIOS_INCLUDE_COM */ +#endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_COM */ + #endif /* PIOS_INCLUDE_USB_HID */ // ADC system diff --git a/flight/PipXtreme/pios_usb_board_data.c b/flight/PipXtreme/pios_usb_board_data.c new file mode 100644 index 000000000..3e41e5ac9 --- /dev/null +++ b/flight/PipXtreme/pios_usb_board_data.c @@ -0,0 +1,119 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_USB_BOARD Board specific USB definitions + * @brief Board specific USB definitions + * @{ + * + * @file pios_usb_board_data.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Board specific USB definitions + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "pios_usb_board_data.h" /* struct usb_*, USB_* */ +#include "pios_sys.h" /* PIOS_SYS_SerialNumberGet */ +#include "pios_usbhook.h" /* PIOS_USBHOOK_* */ + +static const uint8_t usb_product_id[20] = { + sizeof(usb_product_id), + USB_DESC_TYPE_STRING, + 'P', 0, + 'i', 0, + 'p', 0, + 'X', 0, + 't', 0, + 'r', 0, + 'e', 0, + 'm', 0, + 'e', 0, +}; + +static uint8_t usb_serial_number[52] = { + sizeof(usb_serial_number), + USB_DESC_TYPE_STRING, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0, + 0, 0 +}; + +static const struct usb_string_langid usb_lang_id = { + .bLength = sizeof(usb_lang_id), + .bDescriptorType = USB_DESC_TYPE_STRING, + .bLangID = htousbs(USB_LANGID_ENGLISH_UK), +}; + +static const uint8_t usb_vendor_id[28] = { + sizeof(usb_vendor_id), + USB_DESC_TYPE_STRING, + 'o', 0, + 'p', 0, + 'e', 0, + 'n', 0, + 'p', 0, + 'i', 0, + 'l', 0, + 'o', 0, + 't', 0, + '.', 0, + 'o', 0, + 'r', 0, + 'g', 0 +}; + +int32_t PIOS_USB_BOARD_DATA_Init(void) +{ + /* Load device serial number into serial number string */ + uint8_t sn[25]; + PIOS_SYS_SerialNumberGet((char *)sn); + for (uint8_t i = 0; sn[i] != '\0' && (2 * i) < usb_serial_number[0]; i++) { + usb_serial_number[2 + 2 * i] = sn[i]; + } + + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_PRODUCT, (uint8_t *)&usb_product_id, sizeof(usb_product_id)); + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_SERIAL, (uint8_t *)&usb_serial_number, sizeof(usb_serial_number)); + + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_LANG, (uint8_t *)&usb_lang_id, sizeof(usb_lang_id)); + PIOS_USBHOOK_RegisterString(USB_STRING_DESC_VENDOR, (uint8_t *)&usb_vendor_id, sizeof(usb_vendor_id)); + + return 0; +} diff --git a/flight/PipXtreme/pios_usb_hid_desc.c b/flight/PipXtreme/pios_usb_hid_desc.c deleted file mode 100644 index 157e85831..000000000 --- a/flight/PipXtreme/pios_usb_hid_desc.c +++ /dev/null @@ -1,220 +0,0 @@ -/******************** (C) COPYRIGHT 2010 STMicroelectronics ******************** -* File Name : usb_desc.c -* Author : MCD Application Team -* Version : V3.2.1 -* Date : 07/05/2010 -* Description : Descriptors for Custom HID Demo -******************************************************************************** -* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS -* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME. -* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT, -* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE -* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING -* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. -*******************************************************************************/ - -#include "usb_lib.h" -#include "pios_usb.h" -#include "pios_usb_hid.h" -#include "pios_usb_hid_desc.h" - -// ************************************************* -// USB Standard Device Descriptor - -const uint8_t PIOS_HID_DeviceDescriptor[PIOS_HID_SIZ_DEVICE_DESC] = - { - 0x12, // bLength - USB_DEVICE_DESCRIPTOR_TYPE, // bDescriptorType - 0x00, // bcdUSB - 0x02, - 0x00, // bDeviceClass - 0x00, // bDeviceSubClass - 0x00, // bDeviceProtocol - 0x40, // bMaxPacketSize40 - (uint8_t)((PIOS_USB_VENDOR_ID) & 0xff), // idVendor - (uint8_t)((PIOS_USB_VENDOR_ID) >> 8), - (uint8_t)((PIOS_USB_PRODUCT_ID) & 0xff), // idProduct - (uint8_t)((PIOS_USB_PRODUCT_ID) >> 8), - (uint8_t)((PIOS_USB_VERSION_ID) & 0xff), // bcdDevice - (uint8_t)((PIOS_USB_VERSION_ID) >> 8), - 0x01, // Index of string descriptor describing manufacturer - 0x02, // Index of string descriptor describing product - 0x03, // Index of string descriptor describing the device serial number - 0x01 // bNumConfigurations - }; - -// ************************************************* -// USB Configuration Descriptor -// All Descriptors (Configuration, Interface, Endpoint, Class, Vendor - -const uint8_t PIOS_HID_ConfigDescriptor[PIOS_HID_SIZ_CONFIG_DESC] = - { - 0x09, // bLength: Configuation Descriptor size - USB_CONFIGURATION_DESCRIPTOR_TYPE, // bDescriptorType: Configuration - PIOS_HID_SIZ_CONFIG_DESC, - // wTotalLength: Bytes returned - 0x00, - 0x01, // bNumInterfaces: 1 interface - 0x01, // bConfigurationValue: Configuration value - 0x00, // iConfiguration: Index of string descriptor describing the configuration - 0xC0, // bmAttributes: Bus powered - 0x7D, // MaxPower 250 mA - needed to power the RF transmitter - - // ************** Descriptor of Custom HID interface **************** - // 09 - 0x09, // bLength: Interface Descriptor size - USB_INTERFACE_DESCRIPTOR_TYPE, // bDescriptorType: Interface descriptor type - 0x00, // bInterfaceNumber: Number of Interface - 0x00, // bAlternateSetting: Alternate setting - 0x02, // bNumEndpoints - 0x03, // bInterfaceClass: HID - 0x00, // bInterfaceSubClass : 1=BOOT, 0=no boot - 0x00, // nInterfaceProtocol : 0=none, 1=keyboard, 2=mouse - 0, // iInterface: Index of string descriptor - - // ******************** Descriptor of Custom HID HID ******************** - // 18 - 0x09, // bLength: HID Descriptor size - HID_DESCRIPTOR_TYPE, // bDescriptorType: HID - 0x10, // bcdHID: HID Class Spec release number - 0x01, - 0x00, // bCountryCode: Hardware target country - 0x01, // bNumDescriptors: Number of HID class descriptors to follow - 0x22, // bDescriptorType - PIOS_HID_SIZ_REPORT_DESC, // wItemLength: Total length of Report descriptor - 0x00, - - // ******************** Descriptor of Custom HID endpoints ****************** - // 27 - 0x07, // bLength: Endpoint Descriptor size - USB_ENDPOINT_DESCRIPTOR_TYPE, // bDescriptorType: - - 0x81, // bEndpointAddress: Endpoint Address (IN) - 0x03, // bmAttributes: Interrupt endpoint - 0x40, // wMaxPacketSize: 2 Bytes max - 0x00, - 0x04, // bInterval: Polling Interval in ms - // 34 - - 0x07, // bLength: Endpoint Descriptor size - USB_ENDPOINT_DESCRIPTOR_TYPE, // bDescriptorType: - // Endpoint descriptor type - 0x01, // bEndpointAddress: - // Endpoint Address (OUT) - 0x03, // bmAttributes: Interrupt endpoint - 0x40, // wMaxPacketSize: 2 Bytes max - 0x00, - 0x04, // bInterval: Polling Interval in ms - // 41 - }; - -// ************************************************* - - const uint8_t PIOS_HID_ReportDescriptor[PIOS_HID_SIZ_REPORT_DESC] = - { - 0x06, 0x9c, 0xff, // USAGE_PAGE (Vendor Page: 0xFF00) - 0x09, 0x01, // USAGE (Demo Kit) - 0xa1, 0x01, // COLLECTION (Application) - // 6 - - // Data 1 - 0x85, 0x01, // REPORT_ID (1) - 0x09, 0x02, // USAGE (LED 1) - 0x15, 0x00, // LOGICAL_MINIMUM (0) - 0x25, 0xff, // LOGICAL_MAXIMUM (255) - 0x75, 0x08, // REPORT_SIZE (8) - 0x95, PIOS_USB_HID_DATA_LENGTH+1, // REPORT_COUNT (1) - 0x81, 0x83, // INPUT (Const,Var,Array) - // 20 - - // Data 1 - 0x85, 0x02, // REPORT_ID (2) - 0x09, 0x03, // USAGE (LED 1) - 0x15, 0x00, // LOGICAL_MINIMUM (0) - 0x25, 0xff, // LOGICAL_MAXIMUM (255) - 0x75, 0x08, // REPORT_SIZE (8) - 0x95, PIOS_USB_HID_DATA_LENGTH+1, // REPORT_COUNT (1) - 0x91, 0x82, // OUTPUT (Data,Var,Abs,Vol) - // 34 - - 0xc0 // END_COLLECTION - }; - -// ************************************************* -// USB String Descriptors (optional) - -const uint8_t PIOS_HID_StringLangID[PIOS_HID_SIZ_STRING_LANGID] = - { - PIOS_HID_SIZ_STRING_LANGID, - USB_STRING_DESCRIPTOR_TYPE, - 0x09, 0x08 // LangID = 0x0809: UK. English -// 0x09, 0x04 // LangID = 0x0409: U.S. English - }; - -const uint8_t PIOS_HID_StringVendor[PIOS_HID_SIZ_STRING_VENDOR] = - { - PIOS_HID_SIZ_STRING_VENDOR, // Size of Vendor string - USB_STRING_DESCRIPTOR_TYPE, // bDescriptorType - // Manufacturer: "STMicroelectronics" - 'o', 0, - 'p', 0, - 'e', 0, - 'n', 0, - 'p', 0, - 'i', 0, - 'l', 0, - 'o', 0, - 't', 0, - '.', 0, - 'o', 0, - 'r', 0, - 'g', 0 - }; - -const uint8_t PIOS_HID_StringProduct[PIOS_HID_SIZ_STRING_PRODUCT] = - { - PIOS_HID_SIZ_STRING_PRODUCT, // bLength - USB_STRING_DESCRIPTOR_TYPE, // bDescriptorType - 'P', 0, - 'i', 0, - 'p', 0, - 'X', 0, - 't', 0, - 'r', 0, - 'e', 0, - 'm', 0, - 'e', 0 - }; - -uint8_t PIOS_HID_StringSerial[PIOS_HID_SIZ_STRING_SERIAL] = - { - PIOS_HID_SIZ_STRING_SERIAL, // bLength - USB_STRING_DESCRIPTOR_TYPE, // bDescriptorType - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0, - 0, 0 - }; - -// ************************************************* diff --git a/flight/PipXtreme/transparent_comms.c b/flight/PipXtreme/transparent_comms.c index b30f5f581..dc5e0384a 100644 --- a/flight/PipXtreme/transparent_comms.c +++ b/flight/PipXtreme/transparent_comms.c @@ -31,6 +31,7 @@ #include "packet_handler.h" #include "saved_settings.h" #include "main.h" +#include "pios_usb.h" /* PIOS_USB_* */ #if defined(PIOS_COM_DEBUG) #define TRANS_DEBUG @@ -70,8 +71,8 @@ void trans_process(void) bool usb_comms = false; // TRUE if we are using the usb port for comms. uint32_t comm_port = PIOS_COM_SERIAL; // default to using the usart comm-port - #if defined(PIOS_INCLUDE_USB_HID) - if (PIOS_USB_HID_CheckAvailable(0)) + #if defined(PIOS_INCLUDE_USB) + if (PIOS_USB_CheckAvailable(0)) { // USB comms is up, use the USB comm-port instead of the USART comm-port usb_comms = true; comm_port = PIOS_COM_TELEM_USB; @@ -88,13 +89,8 @@ void trans_process(void) else if (usb_comms) { // we're using the USB for comms - keep the USART rx buffer empty - int32_t bytes = PIOS_COM_ReceiveBufferUsed(PIOS_COM_SERIAL); - while (bytes > 0) - { - uint8_t c; - PIOS_COM_ReceiveBuffer(PIOS_COM_SERIAL, &c, 1, 0); - bytes--; - } + uint8_t c; + while (PIOS_COM_ReceiveBuffer(PIOS_COM_SERIAL, &c, 1, 0) > 0); } trans_previous_com_port = comm_port; // remember the current comm-port we are using @@ -111,9 +107,6 @@ void trans_process(void) // free space size in the RF packet handler tx buffer uint16_t ph_num = ph_putData_free(connection_index); - // get the number of data bytes received down the comm-port - int32_t com_num = PIOS_COM_ReceiveBufferUsed(comm_port); - // set the USART RTS handshaking line if (!usb_comms) { @@ -126,16 +119,12 @@ void trans_process(void) SERIAL_RTS_SET; // release the USART RTS line // limit number of bytes we will get to the size of the temp buffer - if (com_num > sizeof(trans_temp_buffer1)) - com_num = sizeof(trans_temp_buffer1); - - // limit number of bytes we will get to the size of the free space in the RF packet handler TX buffer - if (com_num > ph_num) - com_num = ph_num; + if (ph_num > sizeof(trans_temp_buffer1)) + ph_num = sizeof(trans_temp_buffer1); // copy data received down the comm-port into our temp buffer register uint16_t bytes_saved = 0; - bytes_saved = PIOS_COM_ReceiveBuffer(comm_port, trans_temp_buffer1, com_num, 0); + bytes_saved = PIOS_COM_ReceiveBuffer(comm_port, trans_temp_buffer1, ph_num, 0); // put the received comm-port data bytes into the RF packet handler TX buffer if (bytes_saved > 0) @@ -146,12 +135,8 @@ void trans_process(void) } else { // empty the comm-ports rx buffer - int32_t com_num = PIOS_COM_ReceiveBufferUsed(comm_port); - while (com_num > 0) { - uint8_t c; - PIOS_COM_ReceiveBuffer(comm_port, &c, 1, 0); - com_num--; - } + uint8_t c; + while (PIOS_COM_ReceiveBuffer(comm_port, &c, 1, 0) > 0); } // ******************** diff --git a/flight/UAVTalk/inc/uavtalk.h b/flight/UAVTalk/inc/uavtalk.h index 71114ce74..3b7f2a2f9 100644 --- a/flight/UAVTalk/inc/uavtalk.h +++ b/flight/UAVTalk/inc/uavtalk.h @@ -46,7 +46,7 @@ typedef struct { typedef void* UAVTalkConnection; // Public functions -UAVTalkConnection UAVTalkInitialize(UAVTalkOutputStream outputStream, uint32_t maxPacketSize); +UAVTalkConnection UAVTalkInitialize(UAVTalkOutputStream outputStream); int32_t UAVTalkSetOutputStream(UAVTalkConnection connection, UAVTalkOutputStream outputStream); UAVTalkOutputStream UAVTalkGetOutputStream(UAVTalkConnection connection); int32_t UAVTalkSendObject(UAVTalkConnection connection, UAVObjHandle obj, uint16_t instId, uint8_t acked, int32_t timeoutMs); diff --git a/flight/UAVTalk/uavtalk.c b/flight/UAVTalk/uavtalk.c index 900dc24b3..844ed5e38 100644 --- a/flight/UAVTalk/uavtalk.c +++ b/flight/UAVTalk/uavtalk.c @@ -48,9 +48,8 @@ static void updateAck(UAVTalkConnectionData *connection, UAVObjHandle obj, uint1 * \return 0 Success * \return -1 Failure */ -UAVTalkConnection UAVTalkInitialize(UAVTalkOutputStream outputStream, uint32_t maxPacketSize) +UAVTalkConnection UAVTalkInitialize(UAVTalkOutputStream outputStream) { - if (maxPacketSize<1) return 0; // allocate object UAVTalkConnectionData * connection = pvPortMalloc(sizeof(UAVTalkConnectionData)); if (!connection) return 0; @@ -60,7 +59,6 @@ UAVTalkConnection UAVTalkInitialize(UAVTalkOutputStream outputStream, uint32_t m connection->outStream = outputStream; connection->lock = xSemaphoreCreateRecursiveMutex(); connection->transLock = xSemaphoreCreateRecursiveMutex(); - connection->txSize = maxPacketSize; // allocate buffers connection->rxBuffer = pvPortMalloc(UAVTALK_MAX_PACKET_LENGTH); if (!connection->rxBuffer) return 0; @@ -646,7 +644,9 @@ static int32_t sendSingleObject(UAVTalkConnectionData *connection, UAVObjHandle int32_t length; int32_t dataOffset; uint32_t objId; - + + if (!connection->outStream) return -1; + // Setup type and object id fields objId = UAVObjGetID(obj); connection->txBuffer[0] = UAVTALK_SYNC_VAL; // sync byte @@ -701,22 +701,16 @@ static int32_t sendSingleObject(UAVTalkConnectionData *connection, UAVObjHandle // Calculate checksum connection->txBuffer[dataOffset+length] = PIOS_CRC_updateCRC(0, connection->txBuffer, dataOffset+length); - // Send buffer (partially if needed) - uint32_t sent=0; - while (sent < dataOffset+length+UAVTALK_CHECKSUM_LENGTH) { - uint32_t sending = dataOffset+length+UAVTALK_CHECKSUM_LENGTH - sent; - if ( sending > connection->txSize ) sending = connection->txSize; - if ( connection->outStream != NULL ) { - (*connection->outStream)(connection->txBuffer+sent, sending); - } - sent += sending; + uint16_t tx_msg_len = dataOffset+length+UAVTALK_CHECKSUM_LENGTH; + int32_t rc = (*connection->outStream)(connection->txBuffer, tx_msg_len); + + if (rc == tx_msg_len) { + // Update stats + ++connection->stats.txObjects; + connection->stats.txBytes += tx_msg_len; + connection->stats.txObjectBytes += length; } - // Update stats - ++connection->stats.txObjects; - connection->stats.txBytes += dataOffset+length+UAVTALK_CHECKSUM_LENGTH; - connection->stats.txObjectBytes += length; - // Done return 0; } @@ -732,6 +726,8 @@ static int32_t sendNack(UAVTalkConnectionData *connection, uint32_t objId) { int32_t dataOffset; + if (!connection->outStream) return -1; + connection->txBuffer[0] = UAVTALK_SYNC_VAL; // sync byte connection->txBuffer[1] = UAVTALK_TYPE_NACK; // data length inserted here below @@ -749,11 +745,13 @@ static int32_t sendNack(UAVTalkConnectionData *connection, uint32_t objId) // Calculate checksum connection->txBuffer[dataOffset] = PIOS_CRC_updateCRC(0, connection->txBuffer, dataOffset); - // Send buffer - if (connection->outStream!=NULL) (*connection->outStream)(connection->txBuffer, dataOffset+UAVTALK_CHECKSUM_LENGTH); + uint16_t tx_msg_len = dataOffset+UAVTALK_CHECKSUM_LENGTH; + int32_t rc = (*connection->outStream)(connection->txBuffer, tx_msg_len); - // Update stats - connection->stats.txBytes += dataOffset+UAVTALK_CHECKSUM_LENGTH; + if (rc == tx_msg_len) { + // Update stats + connection->stats.txBytes += tx_msg_len; + } // Done return 0; diff --git a/ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg b/ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg index d7928b89e..7667ecbb9 100644 --- a/ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg +++ b/ground/openpilotgcs/share/openpilotgcs/diagrams/default/system-health.svg @@ -14,8 +14,8 @@ height="79.57505" id="svg3604" version="1.1" - inkscape:version="0.48.0 r9654" - sodipodi:docname="system-health-path.svg" + inkscape:version="0.47pre4 r22446" + sodipodi:docname="system-health1.svg" inkscape:export-filename="C:\NoBackup\OpenPilot\mainboard-health.png" inkscape:export-xdpi="269.53" inkscape:export-ydpi="269.53" @@ -594,17 +594,17 @@ borderopacity="1.0" inkscape:pageopacity="0.0" inkscape:pageshadow="2" - inkscape:zoom="4.6775775" - inkscape:cx="48.833406" - inkscape:cy="55.424138" - inkscape:current-layer="foreground" + inkscape:zoom="6.6150935" + inkscape:cx="44.907363" + inkscape:cy="47.413196" + inkscape:current-layer="g4794" id="namedview3608" showgrid="false" - inkscape:window-width="1366" - inkscape:window-height="691" + inkscape:window-width="1280" + inkscape:window-height="775" inkscape:window-x="0" - inkscape:window-y="24" - inkscape:window-maximized="1" + inkscape:window-y="25" + inkscape:window-maximized="0" showguides="true" inkscape:guide-bbox="true"> + + + Boot Fault + style="display:none"> pluginsChanged(); + q->m_allPluginsLoaded=true; + emit q->pluginsLoadEnded(); } /*! diff --git a/ground/openpilotgcs/src/libs/extensionsystem/pluginmanager.h b/ground/openpilotgcs/src/libs/extensionsystem/pluginmanager.h index 6182b388e..49bcd5c55 100644 --- a/ground/openpilotgcs/src/libs/extensionsystem/pluginmanager.h +++ b/ground/openpilotgcs/src/libs/extensionsystem/pluginmanager.h @@ -56,7 +56,7 @@ class EXTENSIONSYSTEM_EXPORT PluginManager : public QObject public: static PluginManager *instance(); - + bool allPluginsLoaded(){return m_allPluginsLoaded;} PluginManager(); virtual ~PluginManager(); @@ -115,6 +115,7 @@ signals: void aboutToRemoveObject(QObject *obj); void pluginsChanged(); + void pluginsLoadEnded(); private slots: void startTests(); @@ -122,6 +123,7 @@ private: Internal::PluginManagerPrivate *d; static PluginManager *m_instance; mutable QReadWriteLock m_lock; + bool m_allPluginsLoaded; friend class Internal::PluginManagerPrivate; }; diff --git a/ground/openpilotgcs/src/libs/qextserialport/src/qextserialenumerator_unix.cpp b/ground/openpilotgcs/src/libs/qextserialport/src/qextserialenumerator_unix.cpp index f43a75b68..fd5af0d25 100644 --- a/ground/openpilotgcs/src/libs/qextserialport/src/qextserialenumerator_unix.cpp +++ b/ground/openpilotgcs/src/libs/qextserialport/src/qextserialenumerator_unix.cpp @@ -60,6 +60,9 @@ QList QextSerialEnumerator::getPorts() else if (str.contains("rfcomm")) { inf.friendName = "Bluetooth-serial adapter "+str.remove(0, 6); } + else if (str.contains("ttyACM")) { + inf.friendName = "USB VCP adapter "+str.remove(0, 6); + } inf.enumName = "/dev"; // is there a more helpful name for this? infoList.append(inf); } diff --git a/ground/openpilotgcs/src/plugins/config/camerastabilization.ui b/ground/openpilotgcs/src/plugins/config/camerastabilization.ui index 76ff38fcb..fb27f1654 100644 --- a/ground/openpilotgcs/src/plugins/config/camerastabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/camerastabilization.ui @@ -1,328 +1,740 @@ - - - CameraStabilizationWidget - - - - 0 - 0 - 720 - 567 - - - - Form - - - - - - Enable CameraStabilization module - - - - - - - After enabling the module, you must power cycle before using and configuring. - - - - - - - Qt::Horizontal - - - - - - - Channel Ranges (number of degrees full range) - - - - - - - - Pitch - - - - - - - Yaw - - - - - - - Roll - - - - - - - 180 - - - - - - - 180 - - - - - - - 180 - - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Qt::Horizontal - - - - 212 - 20 - - - - - - - - - - - Channel Mapping (select output channel or none to disable) - - - - - - - - Roll - - - - - - - - None - - - - - - - - - None - - - - - - - - Pitch - - - - - - - - None - - - - - - - - Yaw - - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Qt::Horizontal - - - - 212 - 20 - - - - - - - - - - - - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - QFrame::StyledPanel - - - QFrame::Raised - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 0 - 0 - - - - - 32 - 32 - - - - - true - - - - - - - - :/core/images/helpicon.svg:/core/images/helpicon.svg - - - - 32 - 32 - - - - Ctrl+S - - - false - - - true - - - - - - - Save settings to the board (RAM only). - -This does not save the calibration settings, this is done using the -specific calibration button on top of the screen. - - - Apply - - - - - - - Send settings to the board, and save to the non-volatile memory. - - - Save - - - false - - - - - - - - - - - - + + + CameraStabilizationWidget + + + + 0 + 0 + 720 + 567 + + + + Form + + + + + + QFrame::NoFrame + + + true + + + + + 0 + 0 + 702 + 488 + + + + + + + Enable CameraStabilization module + + + + + + + After enabling the module, you must power cycle before using and configuring. + + + + + + + Qt::Horizontal + + + + + + + Qt::Vertical + + + QSizePolicy::Preferred + + + + 20 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 100 + + + + Basic Settings (Stabilization) + + + + + + Camera yaw angle for 100% output value, deg. + +This value should be tuned for particular gimbal and servo. You also +have to define channel output range using Output configuration tab. + + + 180 + + + 20 + + + + + + + Camera pitch angle for 100% output value, deg. + +This value should be tuned for particular gimbal and servo. You also +have to define channel output range using Output configuration tab. + + + 180 + + + 20 + + + + + + + Camera roll angle for 100% output value, deg. + +This value should be tuned for particular gimbal and servo. You also +have to define channel output range using Output configuration tab. + + + 180 + + + 20 + + + + + + + Yaw output channel for camera gimbal + + + + None + + + + + + + + Pitch output channel for camera gimbal + + + + None + + + + + + + + Roll output channel for camera gimbal + + + + None + + + + + + + + Output Channel + + + + + + + Output Range + + + + + + + Yaw + + + Qt::AlignCenter + + + + + + + Pitch + + + Qt::AlignCenter + + + + + + + Roll + + + Qt::AlignCenter + + + + + + + + + + Qt::Vertical + + + QSizePolicy::Preferred + + + + 20 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 204 + + + + Advanced Settings (Control) + + + + + + Yaw + + + Qt::AlignCenter + + + + + + + Pitch + + + Qt::AlignCenter + + + + + + + Roll + + + Qt::AlignCenter + + + + + + + Input channel to control camera yaw + +Don't forget to map this channel using Input configuration tab. + + + + None + + + + + + + + Input channel to control camera pitch + +Don't forget to map this channel using Input configuration tab. + + + + None + + + + + + + + Input channel to control camera roll + +Don't forget to map this channel using Input configuration tab. + + + + None + + + + + + + + Input Channel + + + + + + + Axis stabilization mode + +Attitude: camera tracks level for the axis. Input controls the deflection. +AxisLock: camera remembers tracking attitude. Input controls the rate of deflection. + + + + Attitude + + + + + + + + Maximum camera yaw deflection for 100% input in Attitude mode, deg. + + + 180 + + + 20 + + + + + + + Maximum camera yaw rate for 100% input in AxisLock mode, deg/s. + + + 180 + + + 50 + + + + + + + Input low-pass filter response time for yaw axis, ms. + +This option smoothes the stick input. Zero value disables LPF. + + + 1000 + + + 150 + + + + + + + Axis stabilization mode + +Attitude: camera tracks level for the axis. Input controls the deflection. +AxisLock: camera remembers tracking attitude. Input controls the rate of deflection. + + + + Attitude + + + + + + + + Maximum camera pitch deflection for 100% input in Attitude mode, deg. + + + 180 + + + 20 + + + + + + + Maximum camera pitch rate for 100% input in AxisLock mode, deg/s. + + + 180 + + + 50 + + + + + + + Input low-pass filter response time for pitch axis, ms. + +This option smoothes the stick input. Zero value disables LPF. + + + 1000 + + + 150 + + + + + + + Axis stabilization mode + +Attitude: camera tracks level for the axis. Input controls the deflection. +AxisLock: camera remembers tracking attitude. Input controls the rate of deflection. + + + + Attitude + + + + + + + + Maximum camera roll deflection for 100% input in Attitude mode, deg. + + + 180 + + + 20 + + + + + + + Maximum camera roll rate for 100% input in AxisLock mode, deg/s. + + + 180 + + + 50 + + + + + + + Input low-pass filter response time for roll axis, ms. + +This option smoothes the stick input. Zero value disables LPF. + + + 1000 + + + 150 + + + + + + + MaxAxisLockRate + + + + + + + Response Time + + + + + + + Input Rate + + + + + + + Input Range + + + + + + + Stabilization Mode + + + + + + + (the same value for Roll, Pitch, Yaw) + + + + + + + Stick input deadband for all axes in AxisLock mode, deg/s. + +When stick input is within the MaxAxisLockRate range, camera tracks +current attitude. Otherwise it starts moving according to input with +rate depending on input value. + +If you have drift in your Tx controls, you may want to increase this +value. + + + 1 + + + 0.100000000000000 + + + 1.000000000000000 + + + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + + + + + + + + + + + + + + QFrame::StyledPanel + + + QFrame::Raised + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 0 + 0 + + + + + 32 + 32 + + + + + true + + + + + + + + :/core/images/helpicon.svg:/core/images/helpicon.svg + + + + 32 + 32 + + + + Ctrl+S + + + false + + + true + + + + + + + Load default CameraStabilization settings except output channels + +Loaded settings are not applied automatically. You have to click the +Apply or Save button afterwards. + + + Reset To Defaults + + + + + + + Send settings to the board but do not save to the non-volatile memory + + + Apply + + + + + + + Send settings to the board and save to the non-volatile memory + + + Save + + + false + + + + + + + + + + + enableCameraStabilization + rollChannel + pitchChannel + yawChannel + rollOutputRange + pitchOutputRange + yawOutputRange + rollInputChannel + pitchInputChannel + yawInputChannel + rollStabilizationMode + pitchStabilizationMode + yawStabilizationMode + rollInputRange + pitchInputRange + yawInputRange + rollInputRate + pitchInputRate + yawInputRate + rollResponseTime + pitchResponseTime + yawResponseTime + MaxAxisLockRate + camerastabilizationHelp + camerastabilizationResetToDefaults + camerastabilizationSaveRAM + camerastabilizationSaveSD + scrollArea + + + + + + diff --git a/ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui b/ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui index 929c9053d..118acb6e4 100644 --- a/ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui +++ b/ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui @@ -71,7 +71,7 @@ - + Qt::Horizontal @@ -84,6 +84,32 @@ + + + + USB HID Port + + + Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft + + + + + + + + + + USB VCP Port + + + Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft + + + + + + @@ -123,6 +149,19 @@ + + + + + 55 + 0 + + + + ComUsbBridge speed: + + + @@ -137,6 +176,13 @@ + + + + Select the speed here. + + + diff --git a/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp b/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp index 1d0f723d0..ed6e6e551 100644 --- a/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp +++ b/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp @@ -44,8 +44,11 @@ ConfigCCHWWidget::ConfigCCHWWidget(QWidget *parent) : ConfigTaskWidget(parent) addUAVObjectToWidgetRelation("HwSettings","CC_FlexiPort",m_telemetry->cbFlexi); addUAVObjectToWidgetRelation("HwSettings","CC_MainPort",m_telemetry->cbTele); addUAVObjectToWidgetRelation("HwSettings","CC_RcvrPort",m_telemetry->cbRcvr); + addUAVObjectToWidgetRelation("HwSettings","USB_HIDPort",m_telemetry->cbUsbHid); + addUAVObjectToWidgetRelation("HwSettings","USB_VCPPort",m_telemetry->cbUsbVcp); addUAVObjectToWidgetRelation("HwSettings","TelemetrySpeed",m_telemetry->telemetrySpeed); addUAVObjectToWidgetRelation("HwSettings","GPSSpeed",m_telemetry->gpsSpeed); + addUAVObjectToWidgetRelation("HwSettings","ComUsbBridgeSpeed",m_telemetry->comUsbBridgeSpeed); connect(m_telemetry->cchwHelp,SIGNAL(clicked()),this,SLOT(openHelp())); enableControls(false); populateWidgets(); @@ -67,11 +70,22 @@ void ConfigCCHWWidget::widgetsContentsChanged() if (((m_telemetry->cbTele->currentIndex() == HwSettings::CC_MAINPORT_TELEMETRY) && (m_telemetry->cbFlexi->currentIndex() == HwSettings::CC_FLEXIPORT_TELEMETRY)) || ((m_telemetry->cbTele->currentIndex() == HwSettings::CC_MAINPORT_GPS) && (m_telemetry->cbFlexi->currentIndex() == HwSettings::CC_FLEXIPORT_GPS)) || - ((m_telemetry->cbTele->currentIndex() == HwSettings::CC_MAINPORT_COMAUX) && (m_telemetry->cbFlexi->currentIndex() == HwSettings::CC_FLEXIPORT_COMAUX))) + ((m_telemetry->cbTele->currentIndex() == HwSettings::CC_MAINPORT_COMAUX) && (m_telemetry->cbFlexi->currentIndex() == HwSettings::CC_FLEXIPORT_COMAUX)) || + ((m_telemetry->cbTele->currentIndex() == HwSettings::CC_MAINPORT_COMBRIDGE) && (m_telemetry->cbFlexi->currentIndex() == HwSettings::CC_FLEXIPORT_COMBRIDGE))) { enableControls(false); m_telemetry->problems->setText(tr("Warning: you have configured both MainPort and FlexiPort for the same function, this currently is not supported")); } + else if ((m_telemetry->cbUsbHid->currentIndex() == HwSettings::USB_HIDPORT_USBTELEMETRY) && (m_telemetry->cbUsbVcp->currentIndex() == HwSettings::USB_VCPPORT_USBTELEMETRY)) + { + enableControls(false); + m_telemetry->problems->setText(tr("Warning: you have configured both USB HID Port and USB VCP Port for the same function, this currently is not supported")); + } + else if ((m_telemetry->cbUsbHid->currentIndex() != HwSettings::USB_HIDPORT_USBTELEMETRY) && (m_telemetry->cbUsbVcp->currentIndex() != HwSettings::USB_VCPPORT_USBTELEMETRY)) + { + enableControls(false); + m_telemetry->problems->setText(tr("Warning: you have disabled USB Telemetry on both USB HID Port and USB VCP Port, this currently is not supported")); + } else { m_telemetry->problems->setText(""); diff --git a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp index a1e6c1afb..eece2e214 100644 --- a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file configcamerastabilizationwidget.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup ConfigPlugin Config Plugin @@ -25,47 +25,69 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ #include "configcamerastabilizationwidget.h" - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - #include "camerastabsettings.h" #include "hwsettings.h" #include "mixersettings.h" #include "actuatorcommand.h" +#include +#include +#include + ConfigCameraStabilizationWidget::ConfigCameraStabilizationWidget(QWidget *parent) : ConfigTaskWidget(parent) { + // TODO: this widget should use the addUAVObjectToWidgetRelation() m_camerastabilization = new Ui_CameraStabilizationWidget(); m_camerastabilization->setupUi(this); - QComboBox * selectors[3] = { + QComboBox *outputs[3] = { m_camerastabilization->rollChannel, m_camerastabilization->pitchChannel, - m_camerastabilization->yawChannel + m_camerastabilization->yawChannel, }; + QComboBox *inputs[3] = { + m_camerastabilization->rollInputChannel, + m_camerastabilization->pitchInputChannel, + m_camerastabilization->yawInputChannel, + }; + + QComboBox *stabilizationMode[3] = { + m_camerastabilization->rollStabilizationMode, + m_camerastabilization->pitchStabilizationMode, + m_camerastabilization->yawStabilizationMode, + }; + + CameraStabSettings *cameraStab = CameraStabSettings::GetInstance(getObjectManager()); + CameraStabSettings::DataFields cameraStabData = cameraStab->getData(); + for (int i = 0; i < 3; i++) { - selectors[i]->clear(); - selectors[i]->addItem("None"); - for (int j = 0; j < ActuatorCommand::CHANNEL_NUMELEM; j++) - selectors[i]->addItem(QString("Channel %1").arg(j+1)); + outputs[i]->clear(); + outputs[i]->addItem("None"); + for (quint32 j = 0; j < ActuatorCommand::CHANNEL_NUMELEM; j++) + outputs[i]->addItem(QString("Channel %1").arg(j+1)); + + UAVObjectField *field; + + field = cameraStab->getField("Input"); + Q_ASSERT(field); + inputs[i]->clear(); + inputs[i]->addItems(field->getOptions()); + inputs[i]->setCurrentIndex(cameraStabData.Input[i]); + + field = cameraStab->getField("StabilizationMode"); + Q_ASSERT(field); + stabilizationMode[i]->clear(); + stabilizationMode[i]->addItems(field->getOptions()); + stabilizationMode[i]->setCurrentIndex(cameraStabData.StabilizationMode[i]); } connectUpdates(); // Connect buttons - connect(m_camerastabilization->camerastabilizationSaveRAM,SIGNAL(clicked()),this,SLOT(applySettings())); - connect(m_camerastabilization->camerastabilizationSaveSD,SIGNAL(clicked()),this,SLOT(saveSettings())); + connect(m_camerastabilization->camerastabilizationResetToDefaults, SIGNAL(clicked()), this, SLOT(resetToDefaults())); + connect(m_camerastabilization->camerastabilizationSaveRAM, SIGNAL(clicked()), this, SLOT(applySettings())); + connect(m_camerastabilization->camerastabilizationSaveSD, SIGNAL(clicked()), this, SLOT(saveSettings())); connect(m_camerastabilization->camerastabilizationHelp, SIGNAL(clicked()), this, SLOT(openHelp())); } @@ -77,19 +99,19 @@ ConfigCameraStabilizationWidget::~ConfigCameraStabilizationWidget() void ConfigCameraStabilizationWidget::connectUpdates() { // Now connect the widget to the StabilizationSettings object - connect(MixerSettings::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(refreshValues())); - connect(CameraStabSettings::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(refreshValues())); + connect(MixerSettings::GetInstance(getObjectManager()), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshValues())); + connect(CameraStabSettings::GetInstance(getObjectManager()), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshValues())); // TODO: This will need to support both CC and OP later - connect(HwSettings::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(refreshValues())); + connect(HwSettings::GetInstance(getObjectManager()), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshValues())); } void ConfigCameraStabilizationWidget::disconnectUpdates() { // Now connect the widget to the StabilizationSettings object - disconnect(MixerSettings::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(refreshValues())); - disconnect(CameraStabSettings::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(refreshValues())); + disconnect(MixerSettings::GetInstance(getObjectManager()), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshValues())); + disconnect(CameraStabSettings::GetInstance(getObjectManager()), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshValues())); // TODO: This will need to support both CC and OP later - disconnect(HwSettings::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(refreshValues())); + disconnect(HwSettings::GetInstance(getObjectManager()), SIGNAL(objectUpdated(UAVObject *)), this, SLOT(refreshValues())); } /** @@ -99,7 +121,7 @@ void ConfigCameraStabilizationWidget::disconnectUpdates() void ConfigCameraStabilizationWidget::applySettings() { // Enable or disable the settings - HwSettings * hwSettings = HwSettings::GetInstance(getObjectManager()); + HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager()); HwSettings::DataFields hwSettingsData = hwSettings->getData(); hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_CAMERASTAB] = m_camerastabilization->enableCameraStabilization->isChecked() ? @@ -107,14 +129,14 @@ void ConfigCameraStabilizationWidget::applySettings() HwSettings::OPTIONALMODULES_DISABLED; // Update the mixer settings - MixerSettings * mixerSettings = MixerSettings::GetInstance(getObjectManager()); + MixerSettings *mixerSettings = MixerSettings::GetInstance(getObjectManager()); MixerSettings::DataFields mixerSettingsData = mixerSettings->getData(); const int NUM_MIXERS = 10; - QComboBox * selectors[3] = { + QComboBox *outputs[3] = { m_camerastabilization->rollChannel, m_camerastabilization->pitchChannel, - m_camerastabilization->yawChannel + m_camerastabilization->yawChannel, }; // TODO: Need to reformat object so types are an @@ -136,14 +158,14 @@ void ConfigCameraStabilizationWidget::applySettings() for (int i = 0; i < 3; i++) { // Channel 1 is second entry, so becomes zero - int mixerNum = selectors[i]->currentIndex() - 1; + int mixerNum = outputs[i]->currentIndex() - 1; if ( mixerNum >= 0 && // Short circuit in case of none *mixerTypes[mixerNum] != MixerSettings::MIXER1TYPE_DISABLED && (*mixerTypes[mixerNum] != MixerSettings::MIXER1TYPE_CAMERAROLL + i) ) { // If the mixer channel already to something that isn't what we are // about to set it to reset to none - selectors[i]->setCurrentIndex(0); + outputs[i]->setCurrentIndex(0); m_camerastabilization->message->setText("One of the channels is already assigned, reverted to none"); } else { // Make sure no other channels have this output set @@ -158,13 +180,36 @@ void ConfigCameraStabilizationWidget::applySettings() } } - // Update the ranges - CameraStabSettings * cameraStab = CameraStabSettings::GetInstance(getObjectManager()); + // Update the settings + CameraStabSettings *cameraStab = CameraStabSettings::GetInstance(getObjectManager()); CameraStabSettings::DataFields cameraStabData = cameraStab->getData(); + cameraStabData.OutputRange[CameraStabSettings::OUTPUTRANGE_ROLL] = m_camerastabilization->rollOutputRange->value(); cameraStabData.OutputRange[CameraStabSettings::OUTPUTRANGE_PITCH] = m_camerastabilization->pitchOutputRange->value(); cameraStabData.OutputRange[CameraStabSettings::OUTPUTRANGE_YAW] = m_camerastabilization->yawOutputRange->value(); + cameraStabData.Input[CameraStabSettings::INPUT_ROLL] = m_camerastabilization->rollInputChannel->currentIndex(); + cameraStabData.Input[CameraStabSettings::INPUT_PITCH] = m_camerastabilization->pitchInputChannel->currentIndex(); + cameraStabData.Input[CameraStabSettings::INPUT_YAW] = m_camerastabilization->yawInputChannel->currentIndex(); + + cameraStabData.StabilizationMode[CameraStabSettings::STABILIZATIONMODE_ROLL] = m_camerastabilization->rollStabilizationMode->currentIndex(); + cameraStabData.StabilizationMode[CameraStabSettings::STABILIZATIONMODE_PITCH] = m_camerastabilization->pitchStabilizationMode->currentIndex(); + cameraStabData.StabilizationMode[CameraStabSettings::STABILIZATIONMODE_YAW] = m_camerastabilization->yawStabilizationMode->currentIndex(); + + cameraStabData.InputRange[CameraStabSettings::INPUTRANGE_ROLL] = m_camerastabilization->rollInputRange->value(); + cameraStabData.InputRange[CameraStabSettings::INPUTRANGE_PITCH] = m_camerastabilization->pitchInputRange->value(); + cameraStabData.InputRange[CameraStabSettings::INPUTRANGE_YAW] = m_camerastabilization->yawInputRange->value(); + + cameraStabData.InputRate[CameraStabSettings::INPUTRATE_ROLL] = m_camerastabilization->rollInputRate->value(); + cameraStabData.InputRate[CameraStabSettings::INPUTRATE_PITCH] = m_camerastabilization->pitchInputRate->value(); + cameraStabData.InputRate[CameraStabSettings::INPUTRATE_YAW] = m_camerastabilization->yawInputRate->value(); + + cameraStabData.ResponseTime[CameraStabSettings::RESPONSETIME_ROLL] = m_camerastabilization->rollResponseTime->value(); + cameraStabData.ResponseTime[CameraStabSettings::RESPONSETIME_PITCH] = m_camerastabilization->pitchResponseTime->value(); + cameraStabData.ResponseTime[CameraStabSettings::RESPONSETIME_YAW] = m_camerastabilization->yawResponseTime->value(); + + cameraStabData.MaxAxisLockRate = m_camerastabilization->MaxAxisLockRate->value(); + // Because multiple objects are updated, and all of them trigger the callback // they must be done together (if update one then load settings from second // the first update would wipe the UI controls). However to be extra cautious @@ -182,7 +227,7 @@ void ConfigCameraStabilizationWidget::applySettings() void ConfigCameraStabilizationWidget::saveSettings() { applySettings(); - UAVObject * obj = HwSettings::GetInstance(getObjectManager()); + UAVObject *obj = HwSettings::GetInstance(getObjectManager()); saveObjectToSD(obj); obj = MixerSettings::GetInstance(getObjectManager()); saveObjectToSD(obj); @@ -190,24 +235,56 @@ void ConfigCameraStabilizationWidget::saveSettings() saveObjectToSD(obj); } +/** + * Refresh UI with new settings of CameraStabSettings object + * (either from active configuration or just loaded defaults + * to be applied or saved) + */ +void ConfigCameraStabilizationWidget::refreshUIValues(CameraStabSettings::DataFields &cameraStabData) +{ + m_camerastabilization->rollOutputRange->setValue(cameraStabData.OutputRange[CameraStabSettings::OUTPUTRANGE_ROLL]); + m_camerastabilization->pitchOutputRange->setValue(cameraStabData.OutputRange[CameraStabSettings::OUTPUTRANGE_PITCH]); + m_camerastabilization->yawOutputRange->setValue(cameraStabData.OutputRange[CameraStabSettings::OUTPUTRANGE_YAW]); + + m_camerastabilization->rollInputChannel->setCurrentIndex(cameraStabData.Input[CameraStabSettings::INPUT_ROLL]); + m_camerastabilization->pitchInputChannel->setCurrentIndex(cameraStabData.Input[CameraStabSettings::INPUT_PITCH]); + m_camerastabilization->yawInputChannel->setCurrentIndex(cameraStabData.Input[CameraStabSettings::INPUT_YAW]); + + m_camerastabilization->rollStabilizationMode->setCurrentIndex(cameraStabData.StabilizationMode[CameraStabSettings::STABILIZATIONMODE_ROLL]); + m_camerastabilization->pitchStabilizationMode->setCurrentIndex(cameraStabData.StabilizationMode[CameraStabSettings::STABILIZATIONMODE_PITCH]); + m_camerastabilization->yawStabilizationMode->setCurrentIndex(cameraStabData.StabilizationMode[CameraStabSettings::STABILIZATIONMODE_YAW]); + + m_camerastabilization->rollInputRange->setValue(cameraStabData.InputRange[CameraStabSettings::INPUTRANGE_ROLL]); + m_camerastabilization->pitchInputRange->setValue(cameraStabData.InputRange[CameraStabSettings::INPUTRANGE_PITCH]); + m_camerastabilization->yawInputRange->setValue(cameraStabData.InputRange[CameraStabSettings::INPUTRANGE_YAW]); + + m_camerastabilization->rollInputRate->setValue(cameraStabData.InputRate[CameraStabSettings::INPUTRATE_ROLL]); + m_camerastabilization->pitchInputRate->setValue(cameraStabData.InputRate[CameraStabSettings::INPUTRATE_PITCH]); + m_camerastabilization->yawInputRate->setValue(cameraStabData.InputRate[CameraStabSettings::INPUTRATE_YAW]); + + m_camerastabilization->rollResponseTime->setValue(cameraStabData.ResponseTime[CameraStabSettings::RESPONSETIME_ROLL]); + m_camerastabilization->pitchResponseTime->setValue(cameraStabData.ResponseTime[CameraStabSettings::RESPONSETIME_PITCH]); + m_camerastabilization->yawResponseTime->setValue(cameraStabData.ResponseTime[CameraStabSettings::RESPONSETIME_YAW]); + + m_camerastabilization->MaxAxisLockRate->setValue(cameraStabData.MaxAxisLockRate); +} + void ConfigCameraStabilizationWidget::refreshValues() { - HwSettings * hwSettings = HwSettings::GetInstance(getObjectManager()); + HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager()); HwSettings::DataFields hwSettingsData = hwSettings->getData(); m_camerastabilization->enableCameraStabilization->setChecked( hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_CAMERASTAB] == HwSettings::OPTIONALMODULES_ENABLED); - CameraStabSettings * cameraStabSettings = CameraStabSettings::GetInstance(getObjectManager()); - CameraStabSettings::DataFields cameraStab = cameraStabSettings->getData(); - m_camerastabilization->rollOutputRange->setValue(cameraStab.OutputRange[CameraStabSettings::OUTPUTRANGE_ROLL]); - m_camerastabilization->pitchOutputRange->setValue(cameraStab.OutputRange[CameraStabSettings::OUTPUTRANGE_PITCH]); - m_camerastabilization->yawOutputRange->setValue(cameraStab.OutputRange[CameraStabSettings::OUTPUTRANGE_YAW]); + CameraStabSettings *cameraStabSettings = CameraStabSettings::GetInstance(getObjectManager()); + CameraStabSettings::DataFields cameraStabData = cameraStabSettings->getData(); + refreshUIValues(cameraStabData); - MixerSettings * mixerSettings = MixerSettings::GetInstance(getObjectManager()); + MixerSettings *mixerSettings = MixerSettings::GetInstance(getObjectManager()); MixerSettings::DataFields mixerSettingsData = mixerSettings->getData(); const int NUM_MIXERS = 10; - QComboBox * selectors[3] = { + QComboBox *outputs[3] = { m_camerastabilization->rollChannel, m_camerastabilization->pitchChannel, m_camerastabilization->yawChannel @@ -232,21 +309,29 @@ void ConfigCameraStabilizationWidget::refreshValues() { // Default to none if not found. Then search for any mixer channels set to // this - selectors[i]->setCurrentIndex(0); + outputs[i]->setCurrentIndex(0); for (int j = 0; j < NUM_MIXERS; j++) if (*mixerTypes[j] == (MixerSettings::MIXER1TYPE_CAMERAROLL + i) && - selectors[i]->currentIndex() != (j + 1)) - selectors[i]->setCurrentIndex(j + 1); + outputs[i]->currentIndex() != (j + 1)) + outputs[i]->setCurrentIndex(j + 1); } } +void ConfigCameraStabilizationWidget::resetToDefaults() +{ + CameraStabSettings cameraStabDefaults; + CameraStabSettings::DataFields defaults = cameraStabDefaults.getData(); + refreshUIValues(defaults); +} + void ConfigCameraStabilizationWidget::openHelp() { - QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/Camera+Stabilization", QUrl::StrictMode) ); + QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/Camera+Stabilization+Configuration", QUrl::StrictMode) ); } void ConfigCameraStabilizationWidget::enableControls(bool enable) { + m_camerastabilization->camerastabilizationResetToDefaults->setEnabled(enable); m_camerastabilization->camerastabilizationSaveSD->setEnabled(enable); m_camerastabilization->camerastabilizationSaveRAM->setEnabled(enable); } diff --git a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h index f5440e360..4534bdc65 100644 --- a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h @@ -1,8 +1,8 @@ /** ****************************************************************************** * - * @file configahrstwidget.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @file configcamerastabilizationtwidget.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup ConfigPlugin Config Plugin @@ -32,13 +32,6 @@ #include "extensionsystem/pluginmanager.h" #include "uavobjectmanager.h" #include "uavobject.h" -#include -#include -#include -#include -#include -#include - #include "camerastabsettings.h" class ConfigCameraStabilizationWidget: public ConfigTaskWidget @@ -50,12 +43,13 @@ public: ~ConfigCameraStabilizationWidget(); private: - virtual void enableControls(bool enable); - Ui_CameraStabilizationWidget *m_camerastabilization; + virtual void enableControls(bool enable); + void refreshUIValues(CameraStabSettings::DataFields &cameraStabData); private slots: void openHelp(); + void resetToDefaults(); void applySettings(); void saveSettings(); void refreshValues(); @@ -65,4 +59,4 @@ protected: void disconnectUpdates(); }; -#endif // ConfigCameraStabilization_H +#endif // CONFIGCAMERASTABILIZATIONWIDGET_H diff --git a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp index 128f9885b..863104447 100644 --- a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp @@ -622,6 +622,8 @@ void ConfigInputWidget::setChannel(int newChan) m_config->wzText->setText(QString(tr("Please enable throttle hold mode and move the collective pitch stick"))); else if (newChan == ManualControlSettings::CHANNELGROUPS_FLIGHTMODE) m_config->wzText->setText(QString(tr("Please flick the flight mode switch. For switches you may have to repeat this rapidly."))); + else if((transmitterType == heli) && (newChan == ManualControlSettings::CHANNELGROUPS_THROTTLE)) + m_config->wzText->setText(QString(tr("Please disable throttle hold mode and move the throttle stick"))); else m_config->wzText->setText(QString(tr("Please move each control once at a time according to the instructions and picture below.\n\n" "Move the %1 stick")).arg(manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan))); diff --git a/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.cpp b/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.cpp index 9dfa46518..f49d98c0e 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.cpp +++ b/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.cpp @@ -38,6 +38,7 @@ #include #include #include +#include namespace Core { @@ -333,6 +334,12 @@ void ConnectionManager::registerDevice(IConnection *conn, const QString &devN, c */ void ConnectionManager::devChanged(IConnection *connection) { + if(!ExtensionSystem::PluginManager::instance()->allPluginsLoaded()) + { + connectionBackup.append(connection); + connect(ExtensionSystem::PluginManager::instance(),SIGNAL(pluginsLoadEnded()),this,SLOT(connectionsCallBack()),Qt::UniqueConnection); + return; + } //clear device list combobox m_availableDevList->clear(); @@ -381,4 +388,14 @@ void ConnectionManager::devChanged(IConnection *connection) m_connectBtn->setEnabled(false); } +} + +void Core::ConnectionManager::connectionsCallBack() +{ + foreach(IConnection * con,connectionBackup) + { + devChanged(con); + } + connectionBackup.clear(); + disconnect(ExtensionSystem::PluginManager::instance(),SIGNAL(pluginsLoadEnded()),this,SLOT(connectionsCallBack())); } //namespace Core diff --git a/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.h b/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.h index beb809915..289e65590 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.h +++ b/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.h @@ -98,7 +98,7 @@ private slots: // void onConnectionClosed(QObject *obj); void onConnectionDestroyed(QObject *obj); - + void connectionsCallBack(); //used to call devChange after all the plugins are loaded protected: QComboBox *m_availableDevList; QPushButton *m_connectBtn; @@ -114,6 +114,7 @@ protected: private: bool connectDevice(); Internal::MainWindow *m_mainWindow; + QList connectionBackup; }; diff --git a/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrol.ui b/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrol.ui index f48029e47..024db71bb 100644 --- a/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrol.ui +++ b/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrol.ui @@ -20,7 +20,7 @@ Form - background:transparent + @@ -30,42 +30,41 @@ 5 - + + + + - - - - - GCS Control - - - - - - - Armed - - - - - - - Flight Mode: - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - + + + GCS Control + + + + + + + Armed + + + + + + + Flight Mode: + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + - + 10 @@ -121,6 +120,9 @@ 100 + + background:transparent + diff --git a/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrolgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrolgadgetwidget.cpp index d266ec18b..68f0162f5 100644 --- a/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrolgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrolgadgetwidget.cpp @@ -67,7 +67,6 @@ GCSControlGadgetWidget::GCSControlGadgetWidget(QWidget *parent) : QLabel(parent) // Connect object updated event from UAVObject to also update check boxes and dropdown connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(mccChanged(UAVObject*))); - leftX = 0; leftY = 0; rightX = 0; diff --git a/ground/openpilotgcs/src/plugins/notify/notificationitem.cpp b/ground/openpilotgcs/src/plugins/notify/notificationitem.cpp new file mode 100644 index 000000000..a54e7ff89 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/notify/notificationitem.cpp @@ -0,0 +1,435 @@ +/** + ****************************************************************************** + * + * @file NotificationItem.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Notify Plugin configuration + * @see The GNU Public License (GPL) Version 3 + * @defgroup notifyplugin + * @{ + * + *****************************************************************************/ +/* + * 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 + */ + +//Qt headers +#include +#include + +// GCS headers +#include "extensionsystem/pluginmanager.h" +#include "utils/pathutils.h" +#include "uavobjectmanager.h" +#include "uavobject.h" + +// Notify plugin headers +#include "notificationitem.h" +#include "notifylogging.h" + + + + + +QStringList NotificationItem::sayOrderValues; +QStringList NotificationItem::retryValues; + + +NotificationItem::NotificationItem(QObject *parent) + : QObject(parent) + , _currentUpdatePlayed(false) + , isNowPlaying(0) + , _isPlayed(false) + , _timer(NULL) + , _expireTimer(NULL) + , _soundCollectionPath("") + , _currentLanguage("default") + , _dataObject("") + , _objectField("") + , _condition(0) + , _sound1("") + , _sound2("") + , _sound3("") + , _sayOrder(never) + , _singleValue(0) + , _valueRange2(0) + , _repeatValue(repeatInstantly) + , _expireTimeout(eDefaultTimeout) + , _mute(false) +{ + + NotificationItem::sayOrderValues.clear(); + NotificationItem::sayOrderValues.insert(never,QString(tr("Never"))); + NotificationItem::sayOrderValues.insert(beforeFirst,QString(tr("Before first"))); + NotificationItem::sayOrderValues.insert(beforeSecond,QString(tr("Before second"))); + NotificationItem::sayOrderValues.insert(afterSecond,QString(tr("After second"))); + + NotificationItem::retryValues.clear(); + NotificationItem::retryValues.insert(repeatOnce,QString(tr("Repeat Once"))); + NotificationItem::retryValues.insert(repeatOncePerUpdate,QString(tr("Repeat Once per update"))); + NotificationItem::retryValues.insert(repeatInstantly,QString(tr("Repeat Instantly"))); + NotificationItem::retryValues.insert(repeat10seconds,QString(tr("Repeat 10 seconds"))); + NotificationItem::retryValues.insert(repeat30seconds,QString(tr("Repeat 30 seconds"))); + NotificationItem::retryValues.insert(repeat1minute,QString(tr("Repeat 1 minute"))); + +} + +void NotificationItem::copyTo(NotificationItem* that) const +{ + that->isNowPlaying = isNowPlaying; + that->_isPlayed = _isPlayed; + that->_soundCollectionPath = _soundCollectionPath; + that->_currentLanguage = _currentLanguage; + that->_soundCollectionPath = _soundCollectionPath; + that->_dataObject = _dataObject; + that->_objectField = _objectField; + that->_condition = _condition; + that->_sound1 = _sound1; + that->_sound2 = _sound2; + that->_sound3 = _sound3; + that->_sayOrder = _sayOrder; + that->_singleValue = _singleValue; + that->_valueRange2 = _valueRange2; + that->_repeatValue = _repeatValue; + that->_expireTimeout = _expireTimeout; + that->_mute = _mute; + +} + + +void NotificationItem::saveState(QSettings* settings) const +{ + settings->setValue("SoundCollectionPath", Utils::PathUtils().RemoveDataPath(getSoundCollectionPath())); + settings->setValue(QLatin1String("CurrentLanguage"), getCurrentLanguage()); + settings->setValue(QLatin1String("ObjectField"), getObjectField()); + settings->setValue(QLatin1String("DataObject"), getDataObject()); + settings->setValue(QLatin1String("RangeLimit"), getCondition()); + settings->setValue(QLatin1String("Value1"), singleValue()); + settings->setValue(QLatin1String("Value2"), valueRange2()); + settings->setValue(QLatin1String("Sound1"), getSound1()); + settings->setValue(QLatin1String("Sound2"), getSound2()); + settings->setValue(QLatin1String("Sound3"), getSound3()); + settings->setValue(QLatin1String("SayOrder"), getSayOrder()); + settings->setValue(QLatin1String("Repeat"), retryValue()); + settings->setValue(QLatin1String("ExpireTimeout"), lifetime()); + settings->setValue(QLatin1String("Mute"), mute()); +} + +void NotificationItem::restoreState(QSettings* settings) +{ + //settings = Core::ICore::instance()->settings(); + setSoundCollectionPath(Utils::PathUtils().InsertDataPath(settings->value(QLatin1String("SoundCollectionPath"), tr("")).toString())); + setCurrentLanguage(settings->value(QLatin1String("CurrentLanguage"), tr("")).toString()); + setDataObject(settings->value(QLatin1String("DataObject"), tr("")).toString()); + setObjectField(settings->value(QLatin1String("ObjectField"), tr("")).toString()); + setCondition(settings->value(QLatin1String("RangeLimit"), tr("")).toInt()); + setSound1(settings->value(QLatin1String("Sound1"), tr("")).toString()); + setSound2(settings->value(QLatin1String("Sound2"), tr("")).toString()); + setSound3(settings->value(QLatin1String("Sound3"), tr("")).toString()); + setSayOrder(settings->value(QLatin1String("SayOrder"), tr("")).toInt()); + QVariant value = settings->value(QLatin1String("Value1"), tr("")); + setSingleValue(value); + setValueRange2(settings->value(QLatin1String("Value2"), tr("")).toDouble()); + setRetryValue(settings->value(QLatin1String("Repeat"), tr("")).toInt()); + setLifetime(settings->value(QLatin1String("ExpireTimeout"), tr("")).toInt()); + setMute(settings->value(QLatin1String("Mute"), tr("")).toInt()); +} + +void NotificationItem::serialize(QDataStream& stream) +{ + stream << this->_soundCollectionPath; + stream << this->_currentLanguage; + stream << this->_dataObject; + stream << this->_objectField; + stream << this->_condition; + qNotifyDebug()<<"getOptionsPageValues seriaize"<<_condition; + stream << this->_sound1; + stream << this->_sound2; + stream << this->_sound3; + stream << this->_sayOrder; + stream << this->_singleValue; + stream << this->_valueRange2; + stream << this->_repeatValue; + stream << this->_expireTimeout; + stream << this->_mute; +} + +void NotificationItem::deserialize(QDataStream& stream) +{ + stream >> this->_soundCollectionPath; + stream >> this->_currentLanguage; + stream >> this->_dataObject; + stream >> this->_objectField; + stream >> this->_condition; + stream >> this->_sound1; + stream >> this->_sound2; + stream >> this->_sound3; + stream >> this->_sayOrder; + stream >> this->_singleValue; + stream >> this->_valueRange2; + stream >> this->_repeatValue; + stream >> this->_expireTimeout; + stream >> this->_mute; +} + +void NotificationItem::startTimer(int msec) +{ + if (!_timer) { + _timer = new QTimer(this); + _timer->setInterval(msec); + } + if (!_timer->isActive()) + _timer->start(); +} + + +void NotificationItem::restartTimer() +{ + if (!_timer) { + if (!_timer->isActive()) + _timer->start(); + } +} + + +void NotificationItem::stopTimer() +{ + if (_timer) { + if (_timer->isActive()) + _timer->stop(); + } +} + +void NotificationItem::disposeTimer() +{ + if (_timer) { + _timer->stop(); + delete _timer; + _timer = NULL; + } +} + +void NotificationItem::startExpireTimer() +{ + if (!_expireTimer) { + _expireTimer = new QTimer(this); + } + _expireTimer->start(_expireTimeout * 1000); +} + +void NotificationItem::stopExpireTimer() +{ + if (_expireTimer) { + if (_expireTimer) + _expireTimer->stop(); + } +} + +void NotificationItem::disposeExpireTimer() +{ + if (_expireTimer) { + _expireTimer->stop(); + delete _expireTimer; + _expireTimer = NULL; + } +} + +int getValuePosition(QString sayOrder) +{ + return NotificationItem::sayOrderValues.indexOf(sayOrder)-1; +} + +QString NotificationItem::checkSoundExists(QString fileName) +{ + QString name(fileName + ".wav"); + QString filePath = QDir::toNativeSeparators(getSoundCollectionPath() + "/" + + getCurrentLanguage() + "/" + + name); + if(QFile::exists(filePath)) + return filePath; + else { + filePath = QDir::toNativeSeparators(getSoundCollectionPath() + + "/default/" + + name); + if(!QFile::exists(filePath)) + filePath.clear(); + } + return filePath; +} + +QStringList valueToSoundList(QString value) +{ + qNotifyDebug()<<"notificationItem valueToSoundList input param"< number < 1 + digitWavs.append(numberParts.at(1)); + } else { + // append fractional part of number + QString left = numberParts.at(1).left(1); + (left == "0") ? digitWavs.append(left) : digitWavs.append(left + '0'); + digitWavs.append(numberParts.at(1).right(1)); + } + } + qNotifyDebug()<<"notificationItem valueToSoundList return value"<getType()) { + if(!field->getOptions().contains(value.toString())) + return QString(); + str = value.toString(); + } else { + str = QString("%L1").arg(value.toDouble()); + } + return str; +} + +QString NotificationItem::toString() +{ + QString str; + UAVObjectField* field = getUAVObjectField(); + QString value = stringFromValue(singleValue(), field); + + int pos = getSayOrder()-1; + QStringList lst; + lst.append(getSoundCaption(getSound1())); + lst.append(getSoundCaption(getSound2())); + lst.append(getSoundCaption(getSound3())); + QStringList valueSounds = valueToSoundList(value); + bool missed = false; + foreach(QString sound, valueSounds) { + if(checkSoundExists(sound).isEmpty()) { + missed = true; + break; + } + } + + // if not "Never" case + if(-1 != pos) { + if(missed) + lst.insert(pos, "[missed]" + value); + else + lst.insert(pos, value); + } + str = lst.join(" "); + return str; +} + +QStringList& NotificationItem::toSoundList() +{ + // tips: + // check of *.wav files exist needed for playing phonon queues; + // if phonon player don't find next file in queue, it buzz + UAVObjectField* field = getUAVObjectField(); + QString value = stringFromValue(singleValue(), field); + + // generate queue of sound files to play + _messageSequence.clear(); + int pos = getSayOrder()-1; + QStringList lst; + if(!getSound1().isEmpty()) + lst.append(getSound1()); + if(!getSound2().isEmpty()) + lst.append(getSound2()); + if(!getSound3().isEmpty()) + lst.append(getSound3()); + + // if not "Never" case + if(-1 != pos) { + QStringList valueSounds = valueToSoundList(value); + foreach(QString sound, valueSounds) + lst.insert(pos++, sound); + } + + foreach(QString sound, lst) { + QString path = checkSoundExists(sound); + if (!path.isEmpty()) { + _messageSequence.append(path); + } else { + _messageSequence.clear(); + break; + } + } + return _messageSequence; +} + +QString NotificationItem::getSoundCaption(QString fileName) +{ + if(fileName.isEmpty()) return QString(); + if(checkSoundExists(fileName).isEmpty()) { + return QString("[missed]") + fileName; + } + return fileName; +} + +UAVObjectField* NotificationItem::getUAVObjectField() { + return getUAVObject()->getField(getObjectField()); +} + +UAVDataObject* NotificationItem::getUAVObject() { + return dynamic_cast((ExtensionSystem::PluginManager::instance()->getObject())->getObject(getDataObject())); +} diff --git a/ground/openpilotgcs/src/plugins/notify/notificationitem.h b/ground/openpilotgcs/src/plugins/notify/notificationitem.h new file mode 100644 index 000000000..1475fd64f --- /dev/null +++ b/ground/openpilotgcs/src/plugins/notify/notificationitem.h @@ -0,0 +1,217 @@ +/** + ****************************************************************************** + * + * @file NotificationItem.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Notify Plugin configuration header + * @see The GNU Public License (GPL) Version 3 + * @defgroup notifyplugin + * @{ + * + *****************************************************************************/ +/* + * 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 NOTIFICATION_ITEM_H +#define NOTIFICATION_ITEM_H + +#include +#include "qsettings.h" +#include +#include + +using namespace Core; + +#define DECLARE_SOUND(number) \ + QString getSound##number() const { return _sound##number; } \ + void setSound##number(QString text) { _sound##number = text; } \ + +class UAVDataObject; +class UAVObjectField; + +class NotificationItem : public QObject +{ + Q_OBJECT +public: + enum { eDefaultTimeout = 15 }; // in sec + + enum {never,beforeFirst,beforeSecond,afterSecond}; + enum {repeatOncePerUpdate,repeatOnce,repeatInstantly,repeat10seconds, + repeat30seconds,repeat1minute}; + + explicit NotificationItem(QObject *parent = 0); + + void copyTo(NotificationItem*) const; + + DECLARE_SOUND(1) + DECLARE_SOUND(2) + DECLARE_SOUND(3) + + bool getCurrentUpdatePlayed() const {return _currentUpdatePlayed;} + void setCurrentUpdatePlayed(bool value){_currentUpdatePlayed=value;} + + int getCondition() const { return _condition; } + void setCondition(int value) { _condition = value; } + + int getSayOrder() const { return _sayOrder; } + void setSayOrder(int text) { _sayOrder = text; } + + QVariant singleValue() const { return _singleValue; } + void setSingleValue(QVariant value) { _singleValue = value; } + + double valueRange2() const { return _valueRange2; } + void setValueRange2(double value) { _valueRange2 = value; } + + QString getDataObject() const { return _dataObject; } + void setDataObject(QString text) { _dataObject = text; } + + QString getObjectField() const { return _objectField; } + void setObjectField(QString text) { _objectField = text; } + + QString getSoundCollectionPath() const { return _soundCollectionPath; } + void setSoundCollectionPath(QString path) { _soundCollectionPath = path; } + + QString getCurrentLanguage() const { return _currentLanguage; } + void setCurrentLanguage(QString text) { _currentLanguage = text; } + + QStringList getMessageSequence() const { return _messageSequence; } + void setMessageSequence(QStringList sequence) { _messageSequence = sequence; } + + int retryValue() const { return _repeatValue; } + void setRetryValue(int value) { _repeatValue = value; } + + int lifetime() const { return _expireTimeout; } + void setLifetime(int value) { _expireTimeout = value; } + + bool mute() const { return _mute; } + void setMute(bool value) { _mute = value; } + + void saveState(QSettings* settings) const; + void restoreState(QSettings* settings); + + + UAVDataObject* getUAVObject(void); + UAVObjectField* getUAVObjectField(void); + + void serialize(QDataStream& stream); + void deserialize(QDataStream& stream); + + /** + * Convert notification item fields in single string, + * to show in table for example + * + * @return string which describe notification + */ + QString toString(); + + /** + * Generate list of sound files needed to play notification + * + * @return success - reference to non-empty _messageSequence; + * error - if one of sounds doesn't exist returns + * reference to empty _messageSequence; + */ + QStringList& toSoundList(); + + /** + * Returns sound caption name, needed to create string representation of notification. + * + * @return success - string == , if sound file exists + * error - string == [missind], if sound file doesn't exist + */ + QString getSoundCaption(QString fileName); + + + QTimer* getTimer() const { return _timer; } + void startTimer(int value); + void restartTimer(); + void stopTimer(); + void disposeTimer(); + + QTimer* getExpireTimer() const { return _expireTimer; } + void startExpireTimer(); + void stopExpireTimer(); + + void disposeExpireTimer(); + + bool isNowPlaying; + bool _isPlayed; + + static QStringList sayOrderValues; + static QStringList retryValues; + +private: + QString checkSoundExists(QString fileName); + +private: + + bool _currentUpdatePlayed; + + QTimer* _timer; + + //! time from putting notification in queue till moment when notification became out-of-date + //! NOTE: each notification has it lifetime, this time setups individually for each notification + //! according to its priority + QTimer* _expireTimer; + + //! list of wav files from which notification consists + QStringList _messageSequence; + + //! path to folder with sound files + QString _soundCollectionPath; + + //! language in what notifications will be spelled + QString _currentLanguage; + + //! one UAV object per one notification + QString _dataObject; + + //! one field value change can be assigned to one notification + QString _objectField; + + //! fire condition for UAV field value (lower, greater, in range) + int _condition; + + //! possible sounds(at least one required to play notification) + QString _sound1; + QString _sound2; + QString _sound3; + + //! order in what sounds 1-3 will be played + int _sayOrder; + + //! one-side range, value(numeric or ENUM type) maybe lower, greater or in range + QVariant _singleValue; + + //! both-side range, value should be inside the range + //double _valueRange1; + double _valueRange2; + + //! how often or what periodicaly notification should be played + int _repeatValue; + + //! time after event occured till notification became invalid + //! and will be removed from list + int _expireTimeout; + + //! enables/disables playing of current notification + bool _mute; +}; + +Q_DECLARE_METATYPE(NotificationItem*) + +#endif // NotificationItem_H diff --git a/ground/openpilotgcs/src/plugins/notify/notify.pro b/ground/openpilotgcs/src/plugins/notify/notify.pro index 9ebebfa22..fca92db99 100644 --- a/ground/openpilotgcs/src/plugins/notify/notify.pro +++ b/ground/openpilotgcs/src/plugins/notify/notify.pro @@ -10,15 +10,17 @@ QT += phonon HEADERS += notifyplugin.h \ notifypluginoptionspage.h \ - notifypluginconfiguration.h \ notifyitemdelegate.h \ - notifytablemodel.h + notifytablemodel.h \ + notificationitem.h \ + notifylogging.h SOURCES += notifyplugin.cpp \ notifypluginoptionspage.cpp \ - notifypluginconfiguration.cpp \ notifyitemdelegate.cpp \ - notifytablemodel.cpp + notifytablemodel.cpp \ + notificationitem.cpp \ + notifylogging.cpp OTHER_FILES += NotifyPlugin.pluginspec @@ -27,3 +29,5 @@ FORMS += \ RESOURCES += \ res.qrc + + diff --git a/ground/openpilotgcs/src/plugins/notify/notifyitemdelegate.cpp b/ground/openpilotgcs/src/plugins/notify/notifyitemdelegate.cpp index 7a2fc2ef4..da7177b35 100644 --- a/ground/openpilotgcs/src/plugins/notify/notifyitemdelegate.cpp +++ b/ground/openpilotgcs/src/plugins/notify/notifyitemdelegate.cpp @@ -25,136 +25,132 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#include "notifyitemdelegate.h" #include +#include "notifyitemdelegate.h" +#include "notifytablemodel.h" +#include "notifylogging.h" +#include "notificationitem.h" - - NotifyItemDelegate::NotifyItemDelegate(QStringList items,QObject *parent) - : QItemDelegate(parent), - m_parent(parent), - m_items(items) { - - } - - QWidget *NotifyItemDelegate::createEditor(QWidget *parent, - const QStyleOptionViewItem &, - const QModelIndex &index) const - { - if (index.column() == 1) { - QComboBox* editor = new QComboBox(parent); - editor->clear(); - editor->addItems(m_items); - //repeatEditor->setCurrentIndex(0); - //repeatEditor->setItemDelegate(new RepeatCounterDelegate()); - - //connect(repeatEditor,SIGNAL(activated (const QString& )),this,SLOT(selectRow(const QString& ))); - //QTableWidgetItem* item = qobject_cast(parent); - //((QTableWidgetItem*)parent)->setSelected(true); -// connect(editor, SIGNAL(editingFinished()), -// this, SLOT(commitAndCloseEditor())); - return editor; - } else - { - if(index.column() == 2) - { - QSpinBox* editor = new QSpinBox(parent); - connect(editor, SIGNAL(editingFinished()), - this, SLOT(commitAndCloseEditor())); - return editor; - } - - } - QLineEdit *editor = new QLineEdit(parent); -// connect(editor, SIGNAL(editingFinished()), -// this, SLOT(commitAndCloseEditor())); - return editor; - } - - void NotifyItemDelegate::commitAndCloseEditor() - { - QLineEdit *editor = qobject_cast(sender()); - if (editor) - { - emit commitData(editor); - emit closeEditor(editor); - - } else { - QComboBox* editor = qobject_cast(sender()); - if (editor) - { - emit commitData(editor); - emit closeEditor(editor); - } else { - QSpinBox* editor = qobject_cast(sender()); - if (editor) - { - emit commitData(editor); - emit closeEditor(editor); - } - } - } - } - - void NotifyItemDelegate::setEditorData(QWidget *editor, - const QModelIndex &index) const - { - QLineEdit *edit = qobject_cast(editor); - if (edit) { - edit->setText(index.model()->data(index, Qt::EditRole).toString()); - } else { - QComboBox * repeatEditor = qobject_cast(editor); - if (repeatEditor) - repeatEditor->setCurrentIndex(repeatEditor->findText(index.model()->data(index, Qt::EditRole).toString())); - else { - QSpinBox * expireEditor = qobject_cast(editor); - if (expireEditor) - expireEditor->setValue(index.model()->data(index, Qt::EditRole).toInt()); - } - } - } - - void NotifyItemDelegate::setModelData(QWidget *editor, - QAbstractItemModel *model, const QModelIndex &index) const - { - QLineEdit *edit = qobject_cast(editor); - if (edit) { - model->setData(index, edit->text()); - } else { - QComboBox * repeatEditor = qobject_cast(editor); - if (repeatEditor) { - model->setData(index, repeatEditor->currentText()); - - } else { - QSpinBox * expireEditor = qobject_cast(editor); - if (expireEditor) { - //expireEditor->interpretText(); - model->setData(index, expireEditor->value(), Qt::EditRole); - } - } - } - } - - -void NotifyItemDelegate::selectRow(const QString & text) +NotifyItemDelegate::NotifyItemDelegate(QObject* parent) + : QItemDelegate(parent) + , _parent(parent) { - //QList list = ((QTableWidget*)(sender()->parent()))->findItems(text,Qt::MatchExactly); - QComboBox* combo = qobject_cast(sender()); - QTableWidget* table = new QTableWidget; - table = (QTableWidget*)(combo->parent()); - qDebug()<columnCount(); - qDebug()<rowCount(); - qDebug()<currentRow(); - //table->setCurrentIndex(1); - //table->findItems(text,Qt::MatchExactly); - //item->model()->index() - //item->setSelected(true); } -QSize NotifyItemDelegate::sizeHint ( const QStyleOptionViewItem & option, - const QModelIndex & index ) const +QWidget *NotifyItemDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& /*none*/, + const QModelIndex& index) const { - QSize s = QItemDelegate::sizeHint(option, index); - s.setHeight(10); - - return s; + if (eRepeatValue == index.column()) { + QComboBox* editor = new QComboBox(parent); + editor->clear(); + editor->addItems(NotificationItem::retryValues); + return editor; + } else { + if (eExpireTimer == index.column()) { + QSpinBox* editor = new QSpinBox(parent); + connect(editor, SIGNAL(editingFinished()), this, SLOT(commitAndCloseEditor())); + return editor; + } else { + if (eTurnOn == index.column()) { + QCheckBox* editor = new QCheckBox(parent); + connect(editor, SIGNAL(editingFinished()), this, SLOT(commitAndCloseEditor())); + return editor; + } + } + } + QLineEdit *editor = new QLineEdit(parent); + return editor; +} + +void NotifyItemDelegate::commitAndCloseEditor() +{ + QLineEdit* editor = qobject_cast(sender()); + if (editor) { + emit commitData(editor); + emit closeEditor(editor); + } else { + QComboBox* editor = qobject_cast(sender()); + if (editor) + { + emit commitData(editor); + emit closeEditor(editor); + } else { + QSpinBox* editor = qobject_cast(sender()); + if (editor) + { + emit commitData(editor); + emit closeEditor(editor); + } else { + QCheckBox* editor = qobject_cast(sender()); + if (editor) + { + emit commitData(editor); + emit closeEditor(editor); + } + } + } + } +} + +void NotifyItemDelegate::setEditorData(QWidget *editor, const QModelIndex &index) const +{ + QLineEdit* edit = qobject_cast(editor); + if (edit) { + edit->setText(index.model()->data(index, Qt::EditRole).toString()); + } else { + QComboBox* repeatEditor = qobject_cast(editor); + if (repeatEditor) + repeatEditor->setCurrentIndex(repeatEditor->findText(index.model()->data(index, Qt::EditRole).toString())); + else { + QSpinBox* expireEditor = qobject_cast(editor); + if (expireEditor) + expireEditor->setValue(index.model()->data(index, Qt::EditRole).toInt()); + else { + QCheckBox* enablePlayEditor = qobject_cast(editor); + if (enablePlayEditor) + enablePlayEditor->setChecked(index.model()->data(index, Qt::EditRole).toBool()); + } + } + } +} + +void NotifyItemDelegate::setModelData(QWidget *editor, QAbstractItemModel *model, const QModelIndex &index) const +{ + QLineEdit *edit = qobject_cast(editor); + if (edit) { + model->setData(index, edit->text()); + } else { + QComboBox * repeatEditor = qobject_cast(editor); + if (repeatEditor) { + model->setData(index, repeatEditor->currentText()); + } else { + QSpinBox * expireEditor = qobject_cast(editor); + if (expireEditor) { + model->setData(index, expireEditor->value(), Qt::EditRole); + } else { + QCheckBox* enablePlayEditor = qobject_cast(editor); + if (enablePlayEditor) { + model->setData(index, enablePlayEditor->isChecked(), Qt::EditRole); + } + } + } + } +} + +void NotifyItemDelegate::selectRow(const QString& text) +{ + QComboBox* combo = qobject_cast(sender()); + QTableWidget* table = new QTableWidget; + table = (QTableWidget*)(combo->parent()); + + qNotifyDebug() << table->columnCount(); + qNotifyDebug() << table->rowCount(); + qNotifyDebug() << table->currentRow(); +} + +QSize NotifyItemDelegate::sizeHint(const QStyleOptionViewItem& option, const QModelIndex& index) const +{ + QSize s = QItemDelegate::sizeHint(option, index); + s.setHeight(10); + return s; } diff --git a/ground/openpilotgcs/src/plugins/notify/notifyitemdelegate.h b/ground/openpilotgcs/src/plugins/notify/notifyitemdelegate.h index 40d6ced20..ace6d4976 100644 --- a/ground/openpilotgcs/src/plugins/notify/notifyitemdelegate.h +++ b/ground/openpilotgcs/src/plugins/notify/notifyitemdelegate.h @@ -31,46 +31,26 @@ #include #include -//class RepeatCounterDelegate : public QItemDelegate -//{ -// Q_OBJECT - -//public: -// RepeatCounterDelegate(QObject *parent = 0); -// QWidget *createEditor(QWidget *parent, const QStyleOptionViewItem &, -// const QModelIndex &index) const; -// void setEditorData(QWidget *editor, const QModelIndex &index) const; -// void setModelData(QWidget *editor, QAbstractItemModel *model, -// const QModelIndex &index) const; - -//private slots: -// void commitAndCloseEditor(); -//}; class NotifyItemDelegate : public QItemDelegate { - Q_OBJECT + Q_OBJECT public: - NotifyItemDelegate(QStringList items, QObject *parent = 0); - QWidget *createEditor(QWidget *parent, const QStyleOptionViewItem &, - const QModelIndex &index) const; - void setEditorData(QWidget *editor, const QModelIndex &index) const; - void setModelData(QWidget *editor, QAbstractItemModel *model, - const QModelIndex &index) const; -// bool editorEvent(QEvent * event, QAbstractItemModel * model, -// const QStyleOptionViewItem & option, const QModelIndex & index ); - QSize sizeHint ( const QStyleOptionViewItem & option, const QModelIndex & index ) const; - -private: - QObject* m_parent; - QStringList m_items; - QComboBox* repeatEditor; - + NotifyItemDelegate(QObject *parent = 0); + QWidget *createEditor(QWidget *parent, const QStyleOptionViewItem &, + const QModelIndex &index) const; + void setEditorData(QWidget *editor, const QModelIndex &index) const; + void setModelData(QWidget *editor, QAbstractItemModel *model, + const QModelIndex &index) const; + QSize sizeHint ( const QStyleOptionViewItem & option, const QModelIndex & index ) const; private slots: - void selectRow(const QString & text); - void commitAndCloseEditor(); + void selectRow(const QString & text); + void commitAndCloseEditor(); + +private: + QObject* _parent; }; #endif // NOTIFYITEMDELEGATE_H diff --git a/ground/openpilotgcs/src/plugins/notify/notifylogging.cpp b/ground/openpilotgcs/src/plugins/notify/notifylogging.cpp new file mode 100644 index 000000000..3cb11d111 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/notify/notifylogging.cpp @@ -0,0 +1,43 @@ +/** + ****************************************************************************** + * + * @file notifylogging.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Uses to logging only inside notify plugin, + * can be convinient turned on/off + * @see The GNU Public License (GPL) Version 3 + * @defgroup notifyplugin + * @{ + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "notifylogging.h" + +#ifdef DEBUG_NOTIFIES_ENABLE +QDebug qNotifyDebug() +{ + return qDebug() << "[NOTIFY_PLG]"; +} +#endif + +#ifndef DEBUG_NOTIFIES_ENABLE +QNoDebug qNotifyDebug() +{ + return QNoDebug(); +} +#endif diff --git a/flight/CopterControl/System/inc/taskmonitor.h b/ground/openpilotgcs/src/plugins/notify/notifylogging.h similarity index 67% rename from flight/CopterControl/System/inc/taskmonitor.h rename to ground/openpilotgcs/src/plugins/notify/notifylogging.h index 511f552f7..43e54f3b7 100644 --- a/flight/CopterControl/System/inc/taskmonitor.h +++ b/ground/openpilotgcs/src/plugins/notify/notifylogging.h @@ -1,42 +1,46 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @{ - * @addtogroup OpenPilotLibraries OpenPilot System Libraries - * @{ - * @file taskmonitor.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Include file of the task monitoring library - * @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 TASKMONITOR_H -#define TASKMONITOR_H - -#include "taskinfo.h" - -int32_t TaskMonitorInitialize(void); -int32_t TaskMonitorAdd(TaskInfoRunningElem task, xTaskHandle handle); -void TaskMonitorUpdateAll(void); - -#endif // TASKMONITOR_H - -/** - * @} - * @} - */ +/** + ****************************************************************************** + * + * @file notifylogging.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Uses to logging only inside notify plugin, + * can be convinient turned on/off + * @see The GNU Public License (GPL) Version 3 + * @defgroup notifyplugin + * @{ + * + *****************************************************************************/ +/* + * 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 NOTIFYLOGGING_H +#define NOTIFYLOGGING_H + +#include "qdebug.h" + +#define DEBUG_NOTIFIES_ENABLE + +#ifdef DEBUG_NOTIFIES_ENABLE +QDebug qNotifyDebug(); +#endif + +#ifndef DEBUG_NOTIFIES_ENABLE +QNoDebug qNotifyDebug(); +#endif + +#define qNotifyDebug_if(test) if(test) qNotifyDebug() + +#endif // NOTIFYLOGGING_H diff --git a/ground/openpilotgcs/src/plugins/notify/notifyplugin.cpp b/ground/openpilotgcs/src/plugins/notify/notifyplugin.cpp index 8735f8b60..5c7d27e75 100644 --- a/ground/openpilotgcs/src/plugins/notify/notifyplugin.cpp +++ b/ground/openpilotgcs/src/plugins/notify/notifyplugin.cpp @@ -26,8 +26,9 @@ */ #include "notifyplugin.h" -#include "notifypluginconfiguration.h" +#include "notificationitem.h" #include "notifypluginoptionspage.h" +#include "notifylogging.h" #include #include #include @@ -37,16 +38,16 @@ #include #include "qxttimer.h" +#include "backendcapabilities.h" static const QString VERSION = "1.0.0"; //#define DEBUG_NOTIFIES + SoundNotifyPlugin::SoundNotifyPlugin() { - phonon.mo = NULL; - configured = false; - // Do nothing + phonon.mo = NULL; } SoundNotifyPlugin::~SoundNotifyPlugin() @@ -54,7 +55,6 @@ SoundNotifyPlugin::~SoundNotifyPlugin() Core::ICore::instance()->saveSettings(this); if (phonon.mo != NULL) delete phonon.mo; - // Do nothing } bool SoundNotifyPlugin::initialize(const QStringList& args, QString *errMsg) @@ -70,15 +70,12 @@ bool SoundNotifyPlugin::initialize(const QStringList& args, QString *errMsg) void SoundNotifyPlugin::extensionsInitialized() { - Core::ICore::instance()->readSettings(this); - if ( !configured ){ - readConfig_0_0_0(); - } + Core::ICore::instance()->readSettings(this); - ExtensionSystem::PluginManager* pm = ExtensionSystem::PluginManager::instance(); - connect(pm, SIGNAL(objectAdded(QObject*)), this, SLOT(onTelemetryManagerAdded(QObject*))); - removedNotifies.clear(); - connectNotifications(); + ExtensionSystem::PluginManager* pm = ExtensionSystem::PluginManager::instance(); + connect(pm, SIGNAL(objectAdded(QObject*)), this, SLOT(onTelemetryManagerAdded(QObject*))); + _toRemoveNotifications.clear(); + connectNotifications(); } void SoundNotifyPlugin::saveConfig( QSettings* settings, UAVConfigInfo *configInfo){ @@ -95,22 +92,19 @@ void SoundNotifyPlugin::saveConfig( QSettings* settings, UAVConfigInfo *configIn settings->endGroup(); settings->beginWriteArray("listNotifies"); - for (int i = 0; i < lstNotifications.size(); i++) { - settings->setArrayIndex(i); - lstNotifications.at(i)->saveState(settings); + for (int i = 0; i < _notificationList.size(); i++) { + settings->setArrayIndex(i); + _notificationList.at(i)->saveState(settings); } settings->endArray(); settings->setValue(QLatin1String("EnableSound"), enableSound); } -void SoundNotifyPlugin::readConfig( QSettings* settings, UAVConfigInfo *configInfo){ - - if ( configInfo->version() == UAVConfigVersion() ){ - // Just for migration to the new format. - configured = false; - return; - } +void SoundNotifyPlugin::readConfig( QSettings* settings, UAVConfigInfo * /* configInfo */) +{ + // Just for migration to the new format. + //Q_ASSERT(configInfo->version() == UAVConfigVersion()); settings->beginReadArray("Current"); settings->setArrayIndex(0); @@ -120,52 +114,20 @@ void SoundNotifyPlugin::readConfig( QSettings* settings, UAVConfigInfo *configIn // read list of notifications from settings int size = settings->beginReadArray("listNotifies"); for (int i = 0; i < size; ++i) { - settings->setArrayIndex(i); - NotifyPluginConfiguration* notification = new NotifyPluginConfiguration; - notification->restoreState(settings); - lstNotifications.append(notification); + settings->setArrayIndex(i); + NotificationItem* notification = new NotificationItem; + notification->restoreState(settings); + _notificationList.append(notification); } settings->endArray(); setEnableSound(settings->value(QLatin1String("EnableSound"),0).toBool()); - - configured = true; } -void SoundNotifyPlugin::readConfig_0_0_0(){ - - settings = Core::ICore::instance()->settings(); - settings->beginGroup(QLatin1String("NotifyPlugin")); - - settings->beginReadArray("Current"); - settings->setArrayIndex(0); - currentNotification.restoreState(settings); - settings->endArray(); - - // read list of notifications from settings - int size = settings->beginReadArray("listNotifies"); - for (int i = 0; i < size; ++i) { - settings->setArrayIndex(i); - NotifyPluginConfiguration* notification = new NotifyPluginConfiguration; - notification->restoreState(settings); - lstNotifications.append(notification); - } - settings->endArray(); - setEnableSound(settings->value(QLatin1String("EnableSound"),0).toBool()); - settings->endGroup(); - - ExtensionSystem::PluginManager* pm = ExtensionSystem::PluginManager::instance(); - connect(pm, SIGNAL(objectAdded(QObject*)), this, SLOT(onTelemetryManagerAdded(QObject*))); - removedNotifies.clear(); - connectNotifications(); - - configured = true; - } - void SoundNotifyPlugin::onTelemetryManagerAdded(QObject* obj) { - telMngr = qobject_cast(obj); - if(telMngr) - connect(telMngr, SIGNAL(disconnected()), this, SLOT(onAutopilotDisconnect())); + telMngr = qobject_cast(obj); + if (telMngr) + connect(telMngr, SIGNAL(disconnected()), this, SLOT(onAutopilotDisconnect())); } void SoundNotifyPlugin::shutdown() @@ -175,340 +137,395 @@ void SoundNotifyPlugin::shutdown() void SoundNotifyPlugin::onAutopilotDisconnect() { - connectNotifications(); + connectNotifications(); } /*! - clear any notify timers from previous flight; - reset will be perform on start of option page + clear any notify timers from previous flight; + reset will be perform on start of option page */ void SoundNotifyPlugin::resetNotification(void) { - //first, reject empty args and unknown fields. - foreach(NotifyPluginConfiguration* notify,lstNotifications) { - if(notify->timer) - { - disconnect(notify->timer, SIGNAL(timeout()), this, SLOT(repeatTimerHandler())); - notify->timer->stop(); - delete notify->timer; - notify->timer = NULL; - } - if(notify->expireTimer) - { - disconnect(notify->expireTimer, SIGNAL(timeout()), this, SLOT(expireTimerHandler())); - notify->expireTimer->stop(); - delete notify->expireTimer; - notify->expireTimer = NULL; - } - } + //first, reject empty args and unknown fields. + foreach(NotificationItem* ntf, _notificationList) { + ntf->disposeTimer(); + disconnect(ntf->getTimer(), SIGNAL(timeout()), this, SLOT(on_timerRepeated_Notification())); + ntf->disposeExpireTimer(); + disconnect(ntf->getExpireTimer(), SIGNAL(timeout()), this, SLOT(on_timerRepeated_Notification())); + } } /*! - update list of notifies; - will be perform on OK or APPLY press of option page + update list of notifies; + will be perform on OK or APPLY press of option page */ -void SoundNotifyPlugin::updateNotificationList(QList list) +void SoundNotifyPlugin::updateNotificationList(QList list) { - removedNotifies.clear(); - resetNotification(); - lstNotifications.clear(); - lstNotifications=list; - connectNotifications(); + _toRemoveNotifications.clear(); + resetNotification(); + _notificationList.clear(); + _notificationList=list; + connectNotifications(); - Core::ICore::instance()->saveSettings(this); + Core::ICore::instance()->saveSettings(this); } void SoundNotifyPlugin::connectNotifications() { - foreach(UAVDataObject* obj,lstNotifiedUAVObjects) { - if (obj != NULL) - disconnect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(appendNotification(UAVObject*))); - } - if(phonon.mo != NULL) { - delete phonon.mo; - phonon.mo = NULL; + foreach(UAVDataObject* obj,lstNotifiedUAVObjects) { + if (obj != NULL) + disconnect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(on_arrived_Notification(UAVObject*))); + } + if (phonon.mo != NULL) { + delete phonon.mo; + phonon.mo = NULL; + } + + if (!enableSound) return; + + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + UAVObjectManager *objManager = pm->getObject(); + + lstNotifiedUAVObjects.clear(); + _pendingNotifications.clear(); + _notificationList.append(_toRemoveNotifications); + _toRemoveNotifications.clear(); + + //first, reject empty args and unknown fields. + foreach(NotificationItem* notify, _notificationList) { + notify->_isPlayed = false; + notify->isNowPlaying=false; + + if(notify->mute()) continue; + // check is all sounds presented for notification, + // if not - we must not subscribe to it at all + if(notify->toSoundList().isEmpty()) continue; + + UAVDataObject* obj = dynamic_cast( objManager->getObject(notify->getDataObject()) ); + if (obj != NULL ) { + if (!lstNotifiedUAVObjects.contains(obj)) { + lstNotifiedUAVObjects.append(obj); + + connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(on_arrived_Notification(UAVObject*))); + } + } else { + qNotifyDebug() << "Error: Object is unknown (" << notify->getDataObject() << ")."; } + } - if(!enableSound) return; - - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager *objManager = pm->getObject(); - - lstNotifiedUAVObjects.clear(); - pendingNotifications.clear(); - lstNotifications.append(removedNotifies); - removedNotifies.clear(); - - //first, reject empty args and unknown fields. - foreach(NotifyPluginConfiguration* notify,lstNotifications) { - notify->firstStart=true; - notify->isNowPlaying=false; - -// if(notify->timer) -// { -// disconnect(notify->timer, SIGNAL(timeout()), this, SLOT(repeatTimerHandler())); -// notify->timer->stop(); -// delete notify->timer; -// notify->timer = NULL; -// } -// if(notify->expireTimer) -// { -// disconnect(notify->expireTimer, SIGNAL(timeout()), this, SLOT(expireTimerHandler())); -// notify->expireTimer->stop(); -// delete notify->expireTimer; -// notify->expireTimer = NULL; -// } - - UAVDataObject* obj = dynamic_cast( objManager->getObject(notify->getDataObject()) ); - if (obj != NULL ) { - if(!lstNotifiedUAVObjects.contains(obj)) { - lstNotifiedUAVObjects.append(obj); - connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(appendNotification(UAVObject*))); - } - } else - std::cout << "Error: Object is unknown (" << notify->getDataObject().toStdString() << ")." << std::endl; - } - - if(lstNotifications.isEmpty()) return; - // set notification message to current event - phonon.mo = Phonon::createPlayer(Phonon::NotificationCategory); - phonon.mo->clearQueue(); - phonon.firstPlay = true; -#ifdef DEBUG_NOTIFIES - QList audioOutputDevices = - Phonon::BackendCapabilities::availableAudioOutputDevices(); - foreach(Phonon::AudioOutputDevice dev, audioOutputDevices) { - qDebug() << "Notify: Audio Output device: " << dev.name() << " - " << dev.description(); - } -#endif - connect(phonon.mo,SIGNAL(stateChanged(Phonon::State,Phonon::State)), - this,SLOT(stateChanged(Phonon::State,Phonon::State))); + if (_notificationList.isEmpty()) return; + // set notification message to current event + phonon.mo = Phonon::createPlayer(Phonon::NotificationCategory); + phonon.mo->clearQueue(); + phonon.firstPlay = true; + QList audioOutputDevices = + Phonon::BackendCapabilities::availableAudioOutputDevices(); + foreach(Phonon::AudioOutputDevice dev, audioOutputDevices) { + qNotifyDebug() << "Notify: Audio Output device: " << dev.name() << " - " << dev.description(); + } + connect(phonon.mo, SIGNAL(stateChanged(Phonon::State,Phonon::State)), + this, SLOT(stateChanged(Phonon::State,Phonon::State))); } -void SoundNotifyPlugin::appendNotification(UAVObject *object) +void SoundNotifyPlugin::on_arrived_Notification(UAVObject *object) { - disconnect(object, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(appendNotification(UAVObject*))); + foreach(NotificationItem* ntf, _notificationList) { + if (object->getName() != ntf->getDataObject()) + continue; - foreach(NotifyPluginConfiguration* notification, lstNotifications) { - if(object->getName()!=notification->getDataObject()) - continue; - if(nowPlayingConfiguration == notification) - continue; + // skip duplicate notifications + if (_nowPlayingNotification == ntf) + continue; - if(notification->getRepeatFlag()!= "Repeat Instantly" && - notification->getRepeatFlag()!= "Repeat Once" && !notification->firstStart) - continue; + // skip periodical notifications + // this condition accepts: + // 1. Periodical notifications played firstly; + // NOTE: At first time it will be played, then it played only by timer, + // when conditions became false firstStart flag has been cleared and + // notification can be accepted again; + // 2. Once time notifications, they removed immediately after first playing; + // 3. Instant notifications(played one by one without interval); + if (ntf->retryValue() != NotificationItem::repeatInstantly && ntf->retryValue() != NotificationItem::repeatOncePerUpdate && + ntf->retryValue() != NotificationItem::repeatOnce && ntf->_isPlayed) + continue; - checkNotificationRule(notification,object); - } - connect(object, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(appendNotification(UAVObject*))); + qNotifyDebug() << QString("new notification: | %1 | %2 | val1: %3 | val2: %4") + .arg(ntf->getDataObject()) + .arg(ntf->getObjectField()) + .arg(ntf->singleValue().toString()) + .arg(ntf->valueRange2()); + + checkNotificationRule(ntf, object); + } + connect(object, SIGNAL(objectUpdated(UAVObject*)), + this, SLOT(on_arrived_Notification(UAVObject*)), Qt::UniqueConnection); } -void SoundNotifyPlugin::checkNotificationRule(NotifyPluginConfiguration* notification, UAVObject* object) +void SoundNotifyPlugin::on_timerRepeated_Notification() { - bool condition=false; - double threshold; - QString direction; - QString fieldName; - threshold = notification->getSpinBoxValue(); - direction = notification->getValue(); - fieldName = notification->getObjectField(); - UAVObjectField* field = object->getField(fieldName); - if (field->getName()!="") { - double value = field->getDouble(); + NotificationItem* notification = static_cast(sender()->parent()); + if (!notification) + return; + // skip duplicate notifications + // WARNING: generally we shoudn't ever trap here + // this means, that timer fires to early and notification overlap itself + if (_nowPlayingNotification == notification) { + qNotifyDebug() << "WARN: on_timerRepeated - notification was skipped!"; + notification->restartTimer(); + return; + } - switch(direction[0].toAscii()) - { - case 'E': - if(value==threshold) - condition = true; - break; - case 'G': - if(value>threshold) - condition = true; - break; - case 'L': - if(valuegetDataObject()) + .arg(notification->getObjectField()) + .arg(notification->toString()); - if(condition) - { - if(!playNotification(notification)) - { - if(!pendingNotifications.contains(notification)) - { - if(notification->timer) - if(notification->timer->isActive()) - notification->timer->stop(); -#ifdef DEBUG_NOTIFIES - qDebug() << "add to pending list - " << notification->parseNotifyMessage(); -#endif - // if audio is busy, start expiration timer - //ms = (notification->getExpiredTimeout()[in sec])*1000 - //QxtTimer::singleShot(notification->getExpireTimeout()*1000, this, SLOT(expirationTimerHandler(NotifyPluginConfiguration*)), qVariantFromValue(notification)); - pendingNotifications.append(notification); - if(!notification->expireTimer) - { - notification->expireTimer = new QTimer(notification); - connect(notification->expireTimer, SIGNAL(timeout()), this, SLOT(expireTimerHandler())); - } - notification->expireTimer->start(notification->getExpireTimeout()*1000); - } - } - } + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + UAVObjectManager *objManager = pm->getObject(); + UAVObject* object = objManager->getObject(notification->getDataObject()); + if (object) + checkNotificationRule(notification,object); } -bool SoundNotifyPlugin::playNotification(NotifyPluginConfiguration* notification) + +void SoundNotifyPlugin::on_expiredTimer_Notification() { - // Check: race condition, if phonon.mo got deleted don't go further - if (phonon.mo == NULL) - return false; + // fire expire timer + NotificationItem* notification = static_cast(sender()->parent()); + if(!notification) + return; + notification->stopExpireTimer(); -#ifdef DEBUG_NOTIFIES - qDebug() << "Phonon State: " << phonon.mo->state(); -#endif - if((phonon.mo->state()==Phonon::PausedState) || - (phonon.mo->state()==Phonon::StoppedState) || - phonon.firstPlay) - { - // don't fire expire timer - //notification->expire = false; - nowPlayingConfiguration = notification; - if(notification->expireTimer) - notification->expireTimer->stop(); + volatile QMutexLocker lock(&_mutex); - if(notification->getRepeatFlag()=="Repeat Once") - { - removedNotifies.append(lstNotifications.takeAt(lstNotifications.indexOf(notification))); - //if(!notification->firstStart) return true; - } - else { - if(notification->getRepeatFlag()!="Repeat Instantly") - { - QRegExp rxlen("(\\d+)"); - QString value; - int timer_value; - int pos = rxlen.indexIn(notification->getRepeatFlag()); - if (pos > -1) { - value = rxlen.cap(1); // "189" - timer_value = (value.toInt()+8)*1000; //ms*1000 + average duration of meassage - } + if (!_pendingNotifications.isEmpty()) { + qNotifyDebug() << QString("expireTimer: %1% | %2 | %3").arg(notification->getDataObject()) + .arg(notification->getObjectField()) + .arg(notification->toString()); - if(!notification->timer) - { - notification->timer = new QTimer(notification); - notification->timer->setInterval(timer_value); - connect(notification->timer, SIGNAL(timeout()), this, SLOT(repeatTimerHandler())); - } - if(!notification->timer->isActive()) - notification->timer->start(); - - //QxtTimer::singleShot(timer_value, this, SLOT(repeatTimerHandler(NotifyPluginConfiguration*)), qVariantFromValue(notification)); - } - } - notification->firstStart=false; - phonon.mo->clear(); - QString str = notification->parseNotifyMessage(); -#ifdef DEBUG_NOTIFIES - qDebug() << "play notification - " << str; -#endif - foreach(QString item, notification->getNotifyMessageList()) { - Phonon::MediaSource *ms = new Phonon::MediaSource(item); - ms->setAutoDelete(true); - phonon.mo->enqueue(*ms); - } - phonon.mo->play(); - phonon.firstPlay = false; // On Linux, you sometimes have to nudge Phonon to play 1 time before - // the state is not "Loading" anymore. - } - else - return false; // if audio is busy - - return true; -} - -//void SoundNotifyPlugin::repeatTimerHandler(NotifyPluginConfiguration* notification) -//{ -// qDebug() << "repeatTimerHandler - " << notification->parseNotifyMessage(); - -// ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); -// UAVObjectManager *objManager = pm->getObject(); -// UAVObject* object = objManager->getObject(notification->getDataObject()); -// if(object) -// checkNotificationRule(notification,object); -//} - -void SoundNotifyPlugin::repeatTimerHandler() -{ - NotifyPluginConfiguration* notification = static_cast(sender()->parent()); -#ifdef DEBUG_NOTIFIES - qDebug() << "repeatTimerHandler - " << notification->parseNotifyMessage(); -#endif - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager *objManager = pm->getObject(); - UAVObject* object = objManager->getObject(notification->getDataObject()); - if(object) - checkNotificationRule(notification,object); -} - -void SoundNotifyPlugin::expireTimerHandler() -{ - // fire expire timer - NotifyPluginConfiguration* notification = static_cast(sender()->parent()); - notification->expireTimer->stop(); - - if(!pendingNotifications.isEmpty()) - { -#ifdef DEBUG_NOTIFIES - qDebug() << "expireTimerHandler - " << notification->parseNotifyMessage(); -#endif - pendingNotifications.removeOne(notification); - } + _pendingNotifications.removeOne(notification); + } } void SoundNotifyPlugin::stateChanged(Phonon::State newstate, Phonon::State oldstate) { Q_UNUSED(oldstate) -#ifdef DEBUG_NOTIFIES - qDebug() << "File length (ms): " << phonon.mo->totalTime(); - qDebug() << "New State: " << newstate; -#endif + //qNotifyDebug() << "File length (ms): " << phonon.mo->totalTime(); #ifndef Q_OS_WIN - // This is a hack to force Linux to wait until the end of the - // wav file before moving to the next in the queue. - // I wish I did not have to go through a #define, but I did not - // manage to make this work on both platforms any other way! - if (phonon.mo->totalTime()>0) - phonon.mo->setTransitionTime(phonon.mo->totalTime()); + // This is a hack to force Linux to wait until the end of the + // wav file before moving to the next in the queue. + // I wish I did not have to go through a #define, but I did not + // manage to make this work on both platforms any other way! + if (phonon.mo->totalTime()>0) + phonon.mo->setTransitionTime(phonon.mo->totalTime()); #endif - if((newstate == Phonon::PausedState) || - (newstate == Phonon::StoppedState)) - { - nowPlayingConfiguration=NULL; - if(!pendingNotifications.isEmpty()) - { - NotifyPluginConfiguration* notification = pendingNotifications.takeFirst(); -#ifdef DEBUG_NOTIFIES - qDebug() << "play audioFree - " << notification->parseNotifyMessage(); -#endif - playNotification(notification); + if ((newstate == Phonon::PausedState) || + (newstate == Phonon::StoppedState)) + { + qNotifyDebug() << "New State: " << QVariant(newstate).toString(); + + volatile QMutexLocker lock(&_mutex); + // assignment to NULL needed to detect that palying is finished + // it's useful in repeat timer handler, where we can detect + // that notification has not overlap with itself + _nowPlayingNotification = NULL; + + if (!_pendingNotifications.isEmpty()) + { + NotificationItem* notification = _pendingNotifications.takeFirst(); + qNotifyDebug_if(notification) << "play audioFree - " << notification->toString(); + playNotification(notification); + qNotifyDebug()<<"end playNotification"; + } + } else { + if (newstate == Phonon::ErrorState) { + if (phonon.mo->errorType()==0) { + qDebug() << "Phonon::ErrorState: ErrorType = " << phonon.mo->errorType(); + phonon.mo->clearQueue(); + } + } + } +} + +bool checkRange(QString fieldValue, QString enumValue, QStringList /* values */, int direction) +{ + + bool ret = false; + switch(direction) + { + case NotifyPluginOptionsPage::equal: + ret = !QString::compare(enumValue, fieldValue, Qt::CaseInsensitive) ? true : false; + break; + + default: + ret = true; + break; + }; + return ret; +} + +bool checkRange(double fieldValue, double min, double max, int direction) +{ + bool ret = false; + //Q_ASSERT(min < max); + switch(direction) + { + case NotifyPluginOptionsPage::equal: + ret = (fieldValue == min); + break; + + case NotifyPluginOptionsPage::bigger: + ret = (fieldValue > min); + break; + + case NotifyPluginOptionsPage::smaller: + ret = (fieldValue < min); + break; + + default: + ret = (fieldValue > min) && (fieldValue < max); + break; + }; + + return ret; +} + +void SoundNotifyPlugin::checkNotificationRule(NotificationItem* notification, UAVObject* object) +{ + if(notification->getDataObject()!=object->getName() || object->getField(notification->getObjectField())==NULL) + return; + bool condition=false; + + if (notification->mute()) + return; + + int direction = notification->getCondition(); + QString fieldName = notification->getObjectField(); + UAVObjectField* field = object->getField(fieldName); + + if (field->getName().isEmpty()) + return; + + QVariant value = field->getValue(); + if(UAVObjectField::ENUM == field->getType()) { + qNotifyDebug()<<"Check range ENUM"<singleValue().toString()<<"|"<getOptions()<<"|"<< + direction<singleValue().toString(), + field->getOptions(), + direction);; + condition = checkRange(value.toString(), + notification->singleValue().toString(), + field->getOptions(), + direction); + } else { + qNotifyDebug()<<"Check range VAL"<singleValue().toString()<<"|"<getOptions()<<"|"<< + direction<singleValue().toDouble(), + notification->valueRange2(), + direction); + condition = checkRange(value.toDouble(), + notification->singleValue().toDouble(), + notification->valueRange2(), + direction); + } + + notification->_isPlayed = condition; + // if condition has been changed, and already in false state + // we should reset _isPlayed flag and stop repeat timer + if (!notification->_isPlayed) { + notification->stopTimer(); + notification->setCurrentUpdatePlayed(false); + return; + } + if(notification->retryValue() == NotificationItem::repeatOncePerUpdate && notification->getCurrentUpdatePlayed()) + return; + volatile QMutexLocker lock(&_mutex); + + if (!playNotification(notification)) { + if (!_pendingNotifications.contains(notification) + && (_nowPlayingNotification != notification)) { + notification->stopTimer(); + + qNotifyDebug() << "add to pending list - " << notification->toString(); + // if audio is busy, start expiration timer + //ms = (notification->getExpiredTimeout()[in sec])*1000 + //QxtTimer::singleShot(notification->getExpireTimeout()*1000, this, SLOT(expirationTimerHandler(NotificationItem*)), qVariantFromValue(notification)); + _pendingNotifications.append(notification); + notification->startExpireTimer(); + connect(notification->getExpireTimer(), SIGNAL(timeout()), + this, SLOT(on_expiredTimer_Notification()), Qt::UniqueConnection); + } + } +} + +bool SoundNotifyPlugin::playNotification(NotificationItem* notification) +{ + if(!notification) + return false; + + // Check: race condition, if phonon.mo got deleted don't go further + if (phonon.mo == NULL) + return false; + + //qNotifyDebug() << "Phonon State: " << phonon.mo->state(); + + if ((phonon.mo->state()==Phonon::PausedState) + || (phonon.mo->state()==Phonon::StoppedState) + || phonon.firstPlay) + { + _nowPlayingNotification = notification; + notification->stopExpireTimer(); + + if (notification->retryValue() == NotificationItem::repeatOnce) { + _toRemoveNotifications.append(_notificationList.takeAt(_notificationList.indexOf(notification))); + } + else if(notification->retryValue() == NotificationItem::repeatOncePerUpdate) + notification->setCurrentUpdatePlayed(true); + else { + if (notification->retryValue() != NotificationItem::repeatInstantly) { + QRegExp rxlen("(\\d+)"); + QString value; + int timer_value=0; + int pos = rxlen.indexIn(NotificationItem::retryValues.at(notification->retryValue())); + if (pos > -1) { + value = rxlen.cap(1); // "189" + + // needs to correct repeat timer value, + // acording to message play duration, + // we don't measure duration of each message, + // simply take average duration + enum { eAverageDurationSec = 8 }; + + enum { eSecToMsec = 1000 }; + + timer_value = (value.toInt() + eAverageDurationSec) * eSecToMsec; } - } else if (newstate == Phonon::ErrorState) - { - if(phonon.mo->errorType()==0) { - qDebug() << "Phonon::ErrorState: ErrorType = " << phonon.mo->errorType(); - phonon.mo->clearQueue(); - } - } -// if(newstate == Phonon::BufferingState) -// qDebug() << "Phonon::BufferingState!!!"; + + notification->startTimer(timer_value); + connect(notification->getTimer(), SIGNAL(timeout()), + this, SLOT(on_timerRepeated_Notification()), Qt::UniqueConnection); + } + } + phonon.mo->clear(); + qNotifyDebug() << "play: " << notification->toString(); + foreach (QString item, notification->toSoundList()) { + Phonon::MediaSource *ms = new Phonon::MediaSource(item); + ms->setAutoDelete(true); + phonon.mo->enqueue(*ms); + } + qNotifyDebug()<<"begin play"; + phonon.mo->play(); + qNotifyDebug()<<"end play"; + phonon.firstPlay = false; // On Linux, you sometimes have to nudge Phonon to play 1 time before + // the state is not "Loading" anymore. + return true; + + } + + return false; } Q_EXPORT_PLUGIN(SoundNotifyPlugin) diff --git a/ground/openpilotgcs/src/plugins/notify/notifyplugin.h b/ground/openpilotgcs/src/plugins/notify/notifyplugin.h index 0d0eb50d8..6a142ff03 100644 --- a/ground/openpilotgcs/src/plugins/notify/notifyplugin.h +++ b/ground/openpilotgcs/src/plugins/notify/notifyplugin.h @@ -32,7 +32,7 @@ #include "uavtalk/telemetrymanager.h" #include "uavobjectmanager.h" #include "uavobject.h" -#include "notifypluginconfiguration.h" +#include "notificationitem.h" #include #include @@ -44,71 +44,69 @@ class NotifyPluginOptionsPage; typedef struct { Phonon::MediaObject* mo; - NotifyPluginConfiguration* notify; - bool firstPlay; + NotificationItem* notify; + bool firstPlay; } PhononObject, *pPhononObject; + class SoundNotifyPlugin : public Core::IConfigurablePlugin -{ - Q_OBJECT -public: - SoundNotifyPlugin(); - ~SoundNotifyPlugin(); +{ + Q_OBJECT +public: + SoundNotifyPlugin(); + ~SoundNotifyPlugin(); - void extensionsInitialized(); - bool initialize(const QStringList & arguments, QString * errorString); - void readConfig( QSettings* qSettings, Core::UAVConfigInfo *configInfo); - void saveConfig( QSettings* qSettings, Core::UAVConfigInfo *configInfo); - void shutdown(); + void extensionsInitialized(); + bool initialize(const QStringList & arguments, QString * errorString); + void readConfig( QSettings* qSettings, Core::UAVConfigInfo *configInfo); + void saveConfig( QSettings* qSettings, Core::UAVConfigInfo *configInfo); + void shutdown(); - QList getListNotifications() { return lstNotifications; } - //void setListNotifications(QList& list_notify) { } - NotifyPluginConfiguration* getCurrentNotification(){ return ¤tNotification;} - - bool getEnableSound() const { return enableSound; } - void setEnableSound(bool value) {enableSound = value; } - + QList getListNotifications() { return _notificationList; } + NotificationItem* getCurrentNotification(){ return ¤tNotification;} + bool getEnableSound() const { return enableSound; } + void setEnableSound(bool value) {enableSound = value; } private: - bool configured; // just for migration,delete later - bool enableSound; - QList< QList* > lstMediaSource; - QStringList mediaSource; - //QMap mapMediaObjects; - QMultiMap mapMediaObjects; + Q_DISABLE_COPY(SoundNotifyPlugin) - QSettings* settings; - - QList lstNotifiedUAVObjects; - - QList lstNotifications; - QList pendingNotifications; - QList removedNotifies; - - NotifyPluginConfiguration currentNotification; - NotifyPluginConfiguration* nowPlayingConfiguration; - - QString m_field; - PhononObject phonon; - NotifyPluginOptionsPage *mop; - TelemetryManager* telMngr; - - bool playNotification(NotifyPluginConfiguration* notification); - void checkNotificationRule(NotifyPluginConfiguration* notification, UAVObject* object); - void readConfig_0_0_0(); + bool playNotification(NotificationItem* notification); + void checkNotificationRule(NotificationItem* notification, UAVObject* object); + void readConfig_0_0_0(); private slots: - void onTelemetryManagerAdded(QObject* obj); - void onAutopilotDisconnect(); - void connectNotifications(); - void updateNotificationList(QList list); - void resetNotification(void); - void appendNotification(UAVObject *object); - void repeatTimerHandler(void); - void expireTimerHandler(void); - void stateChanged(Phonon::State newstate, Phonon::State oldstate); + + void onTelemetryManagerAdded(QObject* obj); + void onAutopilotDisconnect(); + void connectNotifications(); + void updateNotificationList(QList list); + void resetNotification(void); + void on_arrived_Notification(UAVObject *object); + void on_timerRepeated_Notification(void); + void on_expiredTimer_Notification(void); + void stateChanged(Phonon::State newstate, Phonon::State oldstate); + +private: + bool enableSound; + QList< QList* > lstMediaSource; + QStringList mediaSource; + QMultiMap mapMediaObjects; + QSettings* settings; + + QList lstNotifiedUAVObjects; + QList _notificationList; + QList _pendingNotifications; + QList _toRemoveNotifications; + + NotificationItem currentNotification; + NotificationItem* _nowPlayingNotification; + + PhononObject phonon; + NotifyPluginOptionsPage* mop; + TelemetryManager* telMngr; + QMutex _mutex; }; #endif // SOUNDNOTIFYPLUGIN_H diff --git a/ground/openpilotgcs/src/plugins/notify/notifypluginconfiguration.cpp b/ground/openpilotgcs/src/plugins/notify/notifypluginconfiguration.cpp deleted file mode 100644 index 94b88421e..000000000 --- a/ground/openpilotgcs/src/plugins/notify/notifypluginconfiguration.cpp +++ /dev/null @@ -1,245 +0,0 @@ -/** - ****************************************************************************** - * - * @file notifyPluginConfiguration.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Notify Plugin configuration - * @see The GNU Public License (GPL) Version 3 - * @defgroup notifyplugin - * @{ - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "notifypluginconfiguration.h" -#include -#include -#include "utils/pathutils.h" - - -NotifyPluginConfiguration::NotifyPluginConfiguration(QObject *parent) : - QObject(parent), - isNowPlaying(0), - firstStart(1), - soundCollectionPath(""), - currentLanguage("default"), - dataObject(""), - objectField(""), - value("Equal to"), - sound1(""), - sound2(""), - sound3(""), - sayOrder("Never"), - spinBoxValue(0), - repeatString("Repeat Instantly"), - repeatTimeout(true), - expireTimeout(15) - -{ - timer = NULL; - expireTimer = NULL; -} - -void NotifyPluginConfiguration::copyTo(NotifyPluginConfiguration* that) const -{ - - that->isNowPlaying = isNowPlaying; - that->firstStart = firstStart; - that->soundCollectionPath = soundCollectionPath; - that->currentLanguage = currentLanguage; - that->soundCollectionPath = soundCollectionPath; - that->dataObject = dataObject; - that->objectField = objectField; - that->value = value; - that->sound1 = sound1; - that->sound2 = sound2; - that->sound3 = sound3; - that->sayOrder = sayOrder; - that->spinBoxValue = spinBoxValue; - that->repeatString = repeatString; - that->repeatTimeout = repeatTimeout; - that->expireTimeout = expireTimeout; -} - - -void NotifyPluginConfiguration::saveState(QSettings* settings) const -{ - settings->setValue("SoundCollectionPath", Utils::PathUtils().RemoveDataPath(getSoundCollectionPath())); - settings->setValue(QLatin1String("CurrentLanguage"), getCurrentLanguage()); - settings->setValue(QLatin1String("ObjectField"), getObjectField()); - settings->setValue(QLatin1String("DataObject"), getDataObject()); - settings->setValue(QLatin1String("Value"), getValue()); - settings->setValue(QLatin1String("ValueSpinBox"), getSpinBoxValue()); - settings->setValue(QLatin1String("Sound1"), getSound1()); - settings->setValue(QLatin1String("Sound2"), getSound2()); - settings->setValue(QLatin1String("Sound3"), getSound3()); - settings->setValue(QLatin1String("SayOrder"), getSayOrder()); - settings->setValue(QLatin1String("Repeat"), getRepeatFlag()); - settings->setValue(QLatin1String("ExpireTimeout"), getExpireTimeout()); -} - -void NotifyPluginConfiguration::restoreState(QSettings* settings) -{ - //settings = Core::ICore::instance()->settings(); - setSoundCollectionPath(Utils::PathUtils().InsertDataPath(settings->value(QLatin1String("SoundCollectionPath"), tr("")).toString())); - setCurrentLanguage(settings->value(QLatin1String("CurrentLanguage"), tr("")).toString()); - setDataObject(settings->value(QLatin1String("DataObject"), tr("")).toString()); - setObjectField(settings->value(QLatin1String("ObjectField"), tr("")).toString()); - setValue(settings->value(QLatin1String("Value"), tr("")).toString()); - setSound1(settings->value(QLatin1String("Sound1"), tr("")).toString()); - setSound2(settings->value(QLatin1String("Sound2"), tr("")).toString()); - setSound3(settings->value(QLatin1String("Sound3"), tr("")).toString()); - setSayOrder(settings->value(QLatin1String("SayOrder"), tr("")).toString()); - setSpinBoxValue(settings->value(QLatin1String("ValueSpinBox"), tr("")).toDouble()); - setRepeatFlag(settings->value(QLatin1String("Repeat"), tr("")).toString()); - setExpireTimeout(settings->value(QLatin1String("ExpireTimeout"), tr("")).toInt()); -} - - -QString NotifyPluginConfiguration::parseNotifyMessage() -{ - // tips: - // check of *.wav files exist needed for playing phonon queues; - // if phonon player don't find next file in queue, it buzz - - QString str,str1; - str1= getSayOrder(); - str = QString("%L1 ").arg(getSpinBoxValue()); - int position = 0xFF; - // generate queue of sound files to play - notifyMessageList.clear(); - - if(QFile::exists(QDir::toNativeSeparators(getSoundCollectionPath() + "/" + getCurrentLanguage()+"/"+getSound1()+".wav"))) - notifyMessageList.append(QDir::toNativeSeparators(getSoundCollectionPath() + "/" + getCurrentLanguage()+"/"+getSound1()+".wav")); - else - if(QFile::exists(QDir::toNativeSeparators(getSoundCollectionPath() + "/default/"+getSound1()+".wav"))) - notifyMessageList.append(QDir::toNativeSeparators(getSoundCollectionPath() + "/default/"+getSound1()+".wav")); - - if(getSound2()!="") - { - if(QFile::exists(QDir::toNativeSeparators(getSoundCollectionPath() + "/" + getCurrentLanguage()+"/"+getSound2()+".wav"))) - notifyMessageList.append(QDir::toNativeSeparators(getSoundCollectionPath() + "/" + getCurrentLanguage()+"/"+getSound2()+".wav")); - else - if(QFile::exists(QDir::toNativeSeparators(getSoundCollectionPath() + "/default/"+getSound2()+".wav"))) - notifyMessageList.append(QDir::toNativeSeparators(getSoundCollectionPath() + "/default/"+getSound2()+".wav")); - } - - if(getSound3()!="") - { - if(QFile::exists(QDir::toNativeSeparators(getSoundCollectionPath()+ "/" + getCurrentLanguage()+"/"+getSound3()+".wav"))) - notifyMessageList.append(QDir::toNativeSeparators(getSoundCollectionPath()+ "/" + getCurrentLanguage()+"/"+getSound3()+".wav")); - else - if(QFile::exists(QDir::toNativeSeparators(getSoundCollectionPath()+"/default/"+getSound3()+".wav"))) - notifyMessageList.append(QDir::toNativeSeparators(getSoundCollectionPath()+"/default/"+getSound3()+".wav")); - } - - switch(str1.at(0).toAscii()) - { - case 'N'://NEVER: - str = getSound1()+" "+getSound2()+" "+getSound3(); - position = 0xFF; - break; - - case 'B'://BEFORE: - str = QString("%L1 ").arg(getSpinBoxValue())+getSound1()+" "+getSound2()+" "+getSound3(); - position = 0; - break; - - case 'A'://AFTER: - switch(str1.at(6).toAscii()) - { - case 'f': - str = getSound1()+QString(" %L1 ").arg(getSpinBoxValue())+getSound2()+" "+getSound3(); - position = 1; - break; - case 's': - str = getSound1()+" "+getSound2()+QString(" %L1").arg(getSpinBoxValue())+" "+getSound3(); - position = 2; - break; - case 't': - str = getSound1()+" "+getSound2()+" "+getSound3()+QString(" %L1").arg(getSpinBoxValue()); - position = 3; - break; - } - break; - } - - if(position!=0xFF) - { - QStringList numberParts = QString("%1").arg(getSpinBoxValue()).trimmed().split("."); - QStringList numberFiles; - - if((numberParts.at(0).size()==1) || (numberParts.at(0).toInt()<20)) - { - //if(numberParts.at(0)!="0") - numberFiles.append(numberParts.at(0)); - } else { - int i=0; - if(numberParts.at(0).right(2).toInt()<20 && numberParts.at(0).right(2).toInt()!=0) { - if(numberParts.at(0).right(2).toInt()<10) - numberFiles.append(numberParts.at(0).right(1)); - else - numberFiles.append(numberParts.at(0).right(2)); - i=2; - } - for(;i1) { - numberFiles.append("point"); - if((numberParts.at(1).size()==1) /*|| (numberParts.at(1).toInt()<20)*/) - numberFiles.append(numberParts.at(1)); - else { - if(numberParts.at(1).left(1)=="0") - numberFiles.append(numberParts.at(1).left(1)); - else - numberFiles.append(numberParts.at(1).left(1)+'0'); - numberFiles.append(numberParts.at(1).right(1)); - } - } - foreach(QString fileName,numberFiles) { - fileName+=".wav"; - QString filePath = QDir::toNativeSeparators(getSoundCollectionPath()+"/"+ getCurrentLanguage()+"/"+fileName); - if(QFile::exists(filePath)) - notifyMessageList.insert(position++,QDir::toNativeSeparators(getSoundCollectionPath()+ "/"+getCurrentLanguage()+"/"+fileName)); - else { - if(QFile::exists(QDir::toNativeSeparators(getSoundCollectionPath()+"/default/"+fileName))) - notifyMessageList.insert(position++,QDir::toNativeSeparators(getSoundCollectionPath()+"/default/"+fileName)); - else { - notifyMessageList.clear(); - break; // if no some of *.wav files, then don't play number! - } - } - } - } - - //str.replace(QString(".wav | .mp3"), QString("")); - return str; -} diff --git a/ground/openpilotgcs/src/plugins/notify/notifypluginconfiguration.h b/ground/openpilotgcs/src/plugins/notify/notifypluginconfiguration.h deleted file mode 100644 index ad13a82a0..000000000 --- a/ground/openpilotgcs/src/plugins/notify/notifypluginconfiguration.h +++ /dev/null @@ -1,122 +0,0 @@ -/** - ****************************************************************************** - * - * @file notifypluginconfiguration.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Notify Plugin configuration header - * @see The GNU Public License (GPL) Version 3 - * @defgroup notifyplugin - * @{ - * - *****************************************************************************/ -/* - * 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 NOTIFYPLUGINCONFIGURATION_H -#define NOTIFYPLUGINCONFIGURATION_H -#include -#include "qsettings.h" -#include -#include - -using namespace Core; - -class NotifyPluginConfiguration : public QObject -{ - Q_OBJECT -public: - explicit NotifyPluginConfiguration(QObject *parent = 0); - - QTimer* timer; - QTimer* expireTimer; - bool isNowPlaying; // - bool firstStart; - - void copyTo(NotifyPluginConfiguration*) const; - - QString getSound1() const { return sound1; } - void setSound1(QString text) {sound1 = text; } - - QString getSound2() const { return sound2; } - void setSound2(QString text) {sound2 = text; } - - QString getSound3() const { return sound3; } - void setSound3(QString text) {sound3 = text; } - - QString getValue() const { return value; } - void setValue(QString text) {value = text; } - - QString getSayOrder() const { return sayOrder; } - void setSayOrder(QString text) {sayOrder = text; } - - double getSpinBoxValue() const { return spinBoxValue; } - void setSpinBoxValue(double value) {spinBoxValue = value; } - - - QString getDataObject() const { return dataObject; } - void setDataObject(QString text) {dataObject = text; } - - QString getObjectField() const { return objectField; } - void setObjectField(QString text) { objectField = text; } - - QString getSoundCollectionPath() const { return soundCollectionPath; } - void setSoundCollectionPath(QString text) { soundCollectionPath = text; } - - QString getCurrentLanguage() const { return currentLanguage; } - void setCurrentLanguage(QString text) { currentLanguage = text; } - - QStringList getNotifyMessageList() const { return notifyMessageList; } - void setNotifyMessageList(QStringList text) { notifyMessageList = text; } - - QString getRepeatFlag() const { return repeatString; } - void setRepeatFlag(QString value) { repeatString = value; } - - bool getRepeatTimeout() const { return repeatTimeout; } - void setRepeatTimeout(bool value) { repeatTimeout = value; } - - int getExpireTimeout() const { return expireTimeout; } - void setExpireTimeout(int value) { expireTimeout = value; } - - - - void saveState(QSettings* settings) const; - void restoreState(QSettings* settings); - QString parseNotifyMessage(); - -private: - QStringList notifyMessageList; - QString soundCollectionPath; - QString currentLanguage; - QString dataObject; - QString objectField; - - QString value; - QString sound1; - QString sound2; - QString sound3; - QString sayOrder; - double spinBoxValue; - QString repeatString; - bool repeatTimeout; - int repeatTimerValue; - int expireTimeout; - -}; - -Q_DECLARE_METATYPE(NotifyPluginConfiguration*) - -#endif // NOTIFYPLUGINCONFIGURATION_H diff --git a/ground/openpilotgcs/src/plugins/notify/notifypluginoptionspage.cpp b/ground/openpilotgcs/src/plugins/notify/notifypluginoptionspage.cpp index 5dee5678a..fa8ff053f 100644 --- a/ground/openpilotgcs/src/plugins/notify/notifypluginoptionspage.cpp +++ b/ground/openpilotgcs/src/plugins/notify/notifypluginoptionspage.cpp @@ -27,7 +27,7 @@ #include "notifypluginoptionspage.h" #include -#include "notifypluginconfiguration.h" +#include "notificationitem.h" #include "ui_notifypluginoptionspage.h" #include "extensionsystem/pluginmanager.h" #include "utils/pathutils.h" @@ -39,438 +39,597 @@ #include #include #include +#include +#include #include "notifyplugin.h" #include "notifyitemdelegate.h" #include "notifytablemodel.h" +#include "notifylogging.h" -NotifyPluginOptionsPage::NotifyPluginOptionsPage(/*NotifyPluginConfiguration *config,*/ QObject *parent) : - IOptionsPage(parent), - owner((SoundNotifyPlugin*)parent), - currentCollectionPath(""), - privListNotifications(((SoundNotifyPlugin*)parent)->getListNotifications()) +QStringList NotifyPluginOptionsPage::conditionValues; + +NotifyPluginOptionsPage::NotifyPluginOptionsPage(QObject *parent) + : IOptionsPage(parent) + , _objManager(*ExtensionSystem::PluginManager::instance()->getObject()) + , _owner(qobject_cast(parent)) + , _dynamicFieldCondition(NULL) + , _dynamicFieldWidget(NULL) + , _dynamicFieldType(-1) + , _sayOrder(NULL) + , _form(NULL) + , _selectedNotification(NULL) { + NotifyPluginOptionsPage::conditionValues.insert(equal,tr("Equal to")); + NotifyPluginOptionsPage::conditionValues.insert(bigger,tr("Large than")); + NotifyPluginOptionsPage::conditionValues.insert(smaller,tr("Lower than")); + NotifyPluginOptionsPage::conditionValues.insert(inrange,tr("In range")); } +NotifyPluginOptionsPage::~NotifyPluginOptionsPage() +{} -//creates options page widget (uses the UI file) -QWidget *NotifyPluginOptionsPage::createPage(QWidget *parent) +QWidget *NotifyPluginOptionsPage::createPage(QWidget * /* parent */) { + _optionsPage.reset(new Ui::NotifyPluginOptionsPage()); + //main widget + QWidget* optionsPageWidget = new QWidget; + _dynamicFieldWidget = NULL; + _dynamicFieldCondition = NULL; + resetFieldType(); + //save ref to form, needed for binding dynamic fields in future + _form = optionsPageWidget; + //main layout + _optionsPage->setupUi(optionsPageWidget); - options_page = new Ui::NotifyPluginOptionsPage(); - //main widget - QWidget *optionsPageWidget = new QWidget; - //main layout - options_page->setupUi(optionsPageWidget); + _optionsPage->SoundDirectoryPathChooser->setExpectedKind(Utils::PathChooser::Directory); + _optionsPage->SoundDirectoryPathChooser->setPromptDialogTitle(tr("Choose sound collection directory")); - delegateItems.clear(); - listSoundFiles.clear(); + connect(_optionsPage->SoundDirectoryPathChooser, SIGNAL(changed(const QString&)), + this, SLOT(on_clicked_buttonSoundFolder(const QString&))); + connect(_optionsPage->SoundCollectionList, SIGNAL(currentIndexChanged (int)), + this, SLOT(on_changedIndex_soundLanguage(int))); - delegateItems << "Repeat Once" - << "Repeat Instantly" - << "Repeat 10 seconds" - << "Repeat 30 seconds" - << "Repeat 1 minute"; + connect(this, SIGNAL(updateNotifications(QList)), + _owner, SLOT(updateNotificationList(QList))); + //connect(this, SIGNAL(resetNotification()),owner, SLOT(resetNotification())); - options_page->chkEnableSound->setChecked(owner->getEnableSound()); - options_page->SoundDirectoryPathChooser->setExpectedKind(Utils::PathChooser::Directory); - options_page->SoundDirectoryPathChooser->setPromptDialogTitle(tr("Choose sound collection directory")); + _privListNotifications = _owner->getListNotifications(); + // [1] + setSelectedNotification(_owner->getCurrentNotification()); + addDynamicFieldLayout(); + // [2] + updateConfigView(_selectedNotification); - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - objManager = pm->getObject(); + initRulesTable(); + initButtons(); + initPhononPlayer(); - // Fills the combo boxes for the UAVObjects - QList< QList > objList = objManager->getDataObjects(); - foreach (QList list, objList) { - foreach (UAVDataObject* obj, list) { - options_page->UAVObject->addItem(obj->getName()); - } - } + int curr_row = _privListNotifications.indexOf(_selectedNotification); + _notifyRulesSelection->setCurrentIndex(_notifyRulesModel->index(curr_row, 0, QModelIndex()), + QItemSelectionModel::ClearAndSelect | QItemSelectionModel::Rows); - connect(options_page->SoundDirectoryPathChooser, SIGNAL(changed(const QString&)), this, SLOT(on_buttonSoundFolder_clicked(const QString&))); - connect(options_page->SoundCollectionList, SIGNAL(currentIndexChanged (int)), this, SLOT(on_soundLanguage_indexChanged(int))); - connect(options_page->buttonAdd, SIGNAL(pressed()), this, SLOT(on_buttonAddNotification_clicked())); - connect(options_page->buttonDelete, SIGNAL(pressed()), this, SLOT(on_buttonDeleteNotification_clicked())); - connect(options_page->buttonModify, SIGNAL(pressed()), this, SLOT(on_buttonModifyNotification_clicked())); -// connect(options_page->buttonTestSound1, SIGNAL(clicked()), this, SLOT(on_buttonTestSound1_clicked())); -// connect(options_page->buttonTestSound2, SIGNAL(clicked()), this, SLOT(on_buttonTestSound2_clicked())); - connect(options_page->buttonPlayNotification, SIGNAL(clicked()), this, SLOT(on_buttonTestSoundNotification_clicked())); - connect(options_page->chkEnableSound, SIGNAL(toggled(bool)), this, SLOT(on_chkEnableSound_toggled(bool))); - - - connect(options_page->UAVObject, SIGNAL(currentIndexChanged(QString)), this, SLOT(on_UAVObject_indexChanged(QString))); - connect(this, SIGNAL(updateNotifications(QList)), - owner, SLOT(updateNotificationList(QList))); - connect(this, SIGNAL(resetNotification()),owner, SLOT(resetNotification())); - - //emit resetNotification(); - - - privListNotifications.clear(); - - for (int i = 0; i < owner->getListNotifications().size(); ++i) { - NotifyPluginConfiguration* notification = new NotifyPluginConfiguration(); - owner->getListNotifications().at(i)->copyTo(notification); - privListNotifications.append(notification); - } - - updateConfigView(owner->getCurrentNotification()); - - options_page->chkEnableSound->setChecked(owner->getEnableSound()); - - QStringList headerStrings; - headerStrings << "Name" << "Repeats" << "Lifetime,sec"; - - notifyRulesModel = new NotifyTableModel(&privListNotifications,headerStrings); - options_page->notifyRulesView->setModel(notifyRulesModel); - options_page->notifyRulesView->resizeRowsToContents(); - notifyRulesSelection = new QItemSelectionModel(notifyRulesModel); - connect(notifyRulesSelection, SIGNAL(selectionChanged ( const QItemSelection &, const QItemSelection & )), - this, SLOT(on_tableNotification_changeSelection( const QItemSelection & , const QItemSelection & ))); - connect(this, SIGNAL(entryUpdated(int)), - notifyRulesModel, SLOT(entryUpdated(int))); - connect(this, SIGNAL(entryAdded(int)), - notifyRulesModel, SLOT(entryAdded(int))); - - options_page->notifyRulesView->setSelectionModel(notifyRulesSelection); - options_page->notifyRulesView->setItemDelegate(new NotifyItemDelegate(delegateItems,this)); - - options_page->notifyRulesView->setColumnWidth(0,200); - options_page->notifyRulesView->setColumnWidth(1,150); - options_page->notifyRulesView->setColumnWidth(2,100); - - options_page->buttonModify->setEnabled(false); - options_page->buttonDelete->setEnabled(false); - options_page->buttonPlayNotification->setEnabled(false); - -// sound1 = Phonon::createPlayer(Phonon::NotificationCategory); -// sound2 = Phonon::createPlayer(Phonon::NotificationCategory); - notifySound = Phonon::createPlayer(Phonon::NotificationCategory); -// audioOutput = new Phonon::AudioOutput(Phonon::NotificationCategory, this); -// Phonon::createPath(sound1, audioOutput); -// Phonon::createPath(sound2, audioOutput); -// Phonon::createPath(notifySound, audioOutput); - -// connect(sound1,SIGNAL(stateChanged(Phonon::State,Phonon::State)),SLOT(changeButtonText(Phonon::State,Phonon::State))); -// connect(sound2,SIGNAL(stateChanged(Phonon::State,Phonon::State)),SLOT(changeButtonText(Phonon::State,Phonon::State))); - connect(notifySound,SIGNAL(stateChanged(Phonon::State,Phonon::State)), - this,SLOT(changeButtonText(Phonon::State,Phonon::State))); - - return optionsPageWidget; + return optionsPageWidget; } -void NotifyPluginOptionsPage::showPersistentComboBox( const QModelIndex & parent, int start, int end ) -{ -// for (int i=start; itableNotifications->openPersistentEditor(options_page->tableNotifications->item(i,1)); -// } -} - -void NotifyPluginOptionsPage::showPersistentComboBox2( const QModelIndex & topLeft, const QModelIndex & bottomRight ) -{ - //for (QModelIndex i=topLeft; itableNotifications->openPersistentEditor(options_page->tableNotifications->item(options_page->tableNotifications->currentRow(),1)); - } -} - - -void NotifyPluginOptionsPage::getOptionsPageValues(NotifyPluginConfiguration* notification) -{ - notification->setSoundCollectionPath(options_page->SoundDirectoryPathChooser->path()); - notification->setCurrentLanguage(options_page->SoundCollectionList->currentText()); - notification->setDataObject(options_page->UAVObject->currentText()); - notification->setObjectField(options_page->UAVObjectField->currentText()); - notification->setSound1(options_page->Sound1->currentText()); - notification->setSound2(options_page->Sound2->currentText()); - notification->setSound3(options_page->Sound3->currentText()); - notification->setSayOrder(options_page->SayOrder->currentText()); - notification->setValue(options_page->Value->currentText()); - notification->setSpinBoxValue(options_page->ValueSpinBox->value()); - -// if(notifyRulesSelection->currentIndex().row()>-1) -// { -// //qDebug() << "delegate value:" << options_page->tableNotifications->item(options_page->tableNotifications->currentRow(),1)->data(Qt::EditRole); -// notification->setRepeatFlag(notifyRulesModel->data(notifyRulesSelection->currentIndex(),Qt::DisplayRole).toString()); -// } -} - -//////////////////////////////////////////// -// Called when the user presses apply or OK. -// -// Saves the current values -// -//////////////////////////////////////////// void NotifyPluginOptionsPage::apply() { - - getOptionsPageValues(owner->getCurrentNotification()); - - owner->setEnableSound(options_page->chkEnableSound->isChecked()); - //owner->setListNotifications(privListNotifications); - emit updateNotifications(privListNotifications); + getOptionsPageValues(_owner->getCurrentNotification()); + _owner->setEnableSound(_optionsPage->chkEnableSound->isChecked()); + emit updateNotifications(_privListNotifications); } void NotifyPluginOptionsPage::finish() { - disconnect(notifySound,SIGNAL(stateChanged(Phonon::State,Phonon::State)), - this,SLOT(changeButtonText(Phonon::State,Phonon::State))); - if(notifySound) - { - notifySound->stop(); - notifySound->clear(); - } + disconnect(_optionsPage->UAVObjectField, SIGNAL(currentIndexChanged(QString)), + this, SLOT(on_changedIndex_UAVField(QString))); - delete options_page; -} - - - -////////////////////////////////////////////////////////////////////////////// -// Fills in the combo box when value is changed in the -// combo box -////////////////////////////////////////////////////////////////////////////// -void NotifyPluginOptionsPage::on_UAVObject_indexChanged(QString val) { - options_page->UAVObjectField->clear(); - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager *objManager = pm->getObject(); - UAVDataObject* obj = dynamic_cast( objManager->getObject(val) ); - QList fieldList = obj->getFields(); - foreach (UAVObjectField* field, fieldList) { - options_page->UAVObjectField->addItem(field->getName()); + disconnect(_testSound.data(),SIGNAL(stateChanged(Phonon::State,Phonon::State)), + this,SLOT(on_changed_playButtonText(Phonon::State,Phonon::State))); + if (_testSound) { + _testSound->stop(); + _testSound->clear(); } } -// locate collection folder on disk -void NotifyPluginOptionsPage::on_buttonSoundFolder_clicked(const QString& path) +void NotifyPluginOptionsPage::initButtons() { - QDir dirPath(path); - listDirCollections = dirPath.entryList(QDir::AllDirs | QDir::NoDotAndDotDot); - options_page->SoundCollectionList->clear(); - options_page->SoundCollectionList->addItems(listDirCollections); + _optionsPage->chkEnableSound->setChecked(_owner->getEnableSound()); + connect(_optionsPage->chkEnableSound, SIGNAL(toggled(bool)), + this, SLOT(on_toggled_checkEnableSound(bool))); + + _optionsPage->buttonModify->setEnabled(false); + _optionsPage->buttonDelete->setEnabled(false); + _optionsPage->buttonPlayNotification->setEnabled(false); + connect(_optionsPage->buttonAdd, SIGNAL(pressed()), + this, SLOT(on_clicked_buttonAddNotification())); + connect(_optionsPage->buttonDelete, SIGNAL(pressed()), + this, SLOT(on_clicked_buttonDeleteNotification())); + connect(_optionsPage->buttonModify, SIGNAL(pressed()), + this, SLOT(on_clicked_buttonModifyNotification())); + connect(_optionsPage->buttonPlayNotification, SIGNAL(clicked()), + this, SLOT(on_clicked_buttonTestSoundNotification())); } - -void NotifyPluginOptionsPage::on_soundLanguage_indexChanged(int index) +void NotifyPluginOptionsPage::initPhononPlayer() { - options_page->SoundCollectionList->setCurrentIndex(index); + _testSound.reset(Phonon::createPlayer(Phonon::NotificationCategory)); + connect(_testSound.data(),SIGNAL(stateChanged(Phonon::State,Phonon::State)), + this,SLOT(on_changed_playButtonText(Phonon::State,Phonon::State))); + connect(_testSound.data(), SIGNAL(finished(void)), this, SLOT(on_FinishedPlaying(void))); +} - currentCollectionPath = options_page->SoundDirectoryPathChooser->path() + - QDir::toNativeSeparators("/" + options_page->SoundCollectionList->currentText()); +void NotifyPluginOptionsPage::initRulesTable() +{ + qNotifyDebug_if(_notifyRulesModel.isNull()) << "_notifyRulesModel.isNull())"; + qNotifyDebug_if(!_notifyRulesSelection) << "_notifyRulesSelection.isNull())"; + _notifyRulesModel.reset(new NotifyTableModel(_privListNotifications)); + _notifyRulesSelection = new QItemSelectionModel(_notifyRulesModel.data()); - QDir dirPath(currentCollectionPath); - QStringList filters; - filters << "*.mp3" << "*.wav"; - dirPath.setNameFilters(filters); - listSoundFiles = dirPath.entryList(filters); - listSoundFiles.replaceInStrings(QRegExp(".mp3|.wav"), ""); - options_page->Sound1->clear(); - options_page->Sound2->clear(); - options_page->Sound3->clear(); - options_page->Sound1->addItems(listSoundFiles); - options_page->Sound2->addItem(""); - options_page->Sound2->addItems(listSoundFiles); - options_page->Sound3->addItem(""); - options_page->Sound3->addItems(listSoundFiles); + connect(_notifyRulesSelection, SIGNAL(selectionChanged ( const QItemSelection &, const QItemSelection & )), + this, SLOT(on_changedSelection_notifyTable( const QItemSelection & , const QItemSelection & ))); + connect(this, SIGNAL(entryUpdated(int)), + _notifyRulesModel.data(), SLOT(entryUpdated(int))); + + _optionsPage->notifyRulesView->setModel(_notifyRulesModel.data()); + _optionsPage->notifyRulesView->setSelectionModel(_notifyRulesSelection); + _optionsPage->notifyRulesView->setItemDelegate(new NotifyItemDelegate(this)); + + _optionsPage->notifyRulesView->resizeRowsToContents(); + _optionsPage->notifyRulesView->setColumnWidth(eMessageName,200); + _optionsPage->notifyRulesView->setColumnWidth(eRepeatValue,120); + _optionsPage->notifyRulesView->setColumnWidth(eExpireTimer,100); + _optionsPage->notifyRulesView->setColumnWidth(eTurnOn,60); + _optionsPage->notifyRulesView->setDragEnabled(true); + _optionsPage->notifyRulesView->setAcceptDrops(true); + _optionsPage->notifyRulesView->setDropIndicatorShown(true); + _optionsPage->notifyRulesView->setDragDropMode(QAbstractItemView::InternalMove); +} + +UAVObjectField* NotifyPluginOptionsPage::getObjectFieldFromSelected() +{ + return (_currUAVObject) ? _currUAVObject->getField(_selectedNotification->getObjectField()) : NULL; +} + +void NotifyPluginOptionsPage::setSelectedNotification(NotificationItem* ntf) +{ + _selectedNotification = ntf; + _currUAVObject = dynamic_cast(_objManager.getObject(_selectedNotification->getDataObject())); + if(!_currUAVObject) { + qNotifyDebug() << "no such UAVObject: " << _selectedNotification->getDataObject(); + } +} + +void NotifyPluginOptionsPage::addDynamicFieldLayout() +{ + // there is no need to check (objField == NULL), + // thus it doesn't use in this field directly + + QSizePolicy labelSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed); + labelSizePolicy.setHorizontalStretch(0); + labelSizePolicy.setVerticalStretch(0); +// labelSizePolicy.setHeightForWidth(UAVObject->sizePolicy().hasHeightForWidth()); + + + QLabel* labelSayOrder = new QLabel("Say order ", _form); + labelSayOrder->setSizePolicy(labelSizePolicy); + + _optionsPage->dynamicValueLayout->addWidget(labelSayOrder); + _sayOrder = new QComboBox(_form); + _optionsPage->dynamicValueLayout->addWidget(_sayOrder); + _sayOrder->addItems(NotificationItem::sayOrderValues); + + QLabel* labelValueIs = new QLabel("Value is ", _form); + labelValueIs->setSizePolicy(labelSizePolicy); + _optionsPage->dynamicValueLayout->addWidget(labelValueIs); + + _dynamicFieldCondition = new QComboBox(_form); + _optionsPage->dynamicValueLayout->addWidget(_dynamicFieldCondition); + UAVObjectField* field = getObjectFieldFromSelected(); + addDynamicField(field); +} + +void NotifyPluginOptionsPage::addDynamicField(UAVObjectField* objField) +{ + if(!objField) { + qNotifyDebug() << "addDynamicField | input objField == NULL"; + return; + } + if (objField->getType() == _dynamicFieldType) { + if (QComboBox* fieldValue = dynamic_cast(_dynamicFieldWidget)) { + fieldValue->clear(); + QStringList enumValues(objField->getOptions()); + fieldValue->addItems(enumValues); + } + return; + } + + disconnect(_dynamicFieldCondition, SIGNAL(currentIndexChanged(QString)), + this, SLOT(on_changedIndex_rangeValue(QString))); + + _dynamicFieldCondition->clear(); + _dynamicFieldCondition->addItems(NotifyPluginOptionsPage::conditionValues); + if (UAVObjectField::ENUM == objField->getType()) { + _dynamicFieldCondition->removeItem(smaller); + _dynamicFieldCondition->removeItem(bigger); + } + _dynamicFieldCondition->setCurrentIndex(_dynamicFieldCondition->findText(NotifyPluginOptionsPage::conditionValues.at(_selectedNotification->getCondition()))); + + connect(_dynamicFieldCondition, SIGNAL(currentIndexChanged(QString)), + this, SLOT(on_changedIndex_rangeValue(QString))); + + addDynamicFieldWidget(objField); +} + +void NotifyPluginOptionsPage::addDynamicFieldWidget(UAVObjectField* objField) +{ + if(!objField) { + qNotifyDebug() << "objField == NULL!"; + return; + } + // check if dynamic fileld already settled, + // so if its exists remove it and install new field + if (_dynamicFieldWidget) { + _optionsPage->dynamicValueLayout->removeWidget(_dynamicFieldWidget); + delete _dynamicFieldWidget; + _dynamicFieldWidget = NULL; + } + + QSizePolicy sizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed); + sizePolicy.setHorizontalStretch(0); + sizePolicy.setVerticalStretch(0); + + _dynamicFieldType = objField->getType(); + switch(_dynamicFieldType) + { + case UAVObjectField::ENUM: + { + _dynamicFieldWidget = new QComboBox(_form); + QStringList enumValues(objField->getOptions()); + (dynamic_cast(_dynamicFieldWidget))->addItems(enumValues); + } + break; + + default: + Q_ASSERT(_dynamicFieldCondition); + if (NotifyPluginOptionsPage::conditionValues.indexOf(_dynamicFieldCondition->currentText()) == NotifyPluginOptionsPage::inrange) { + _dynamicFieldWidget = new QLineEdit(_form); + + (static_cast(_dynamicFieldWidget))->setInputMask("#999.99 : #999.99;"); + (static_cast(_dynamicFieldWidget))->setText("0000000000"); + (static_cast(_dynamicFieldWidget))->setCursorPosition(0); + } else { + _dynamicFieldWidget = new QDoubleSpinBox(_form); + (dynamic_cast(_dynamicFieldWidget))->setRange(-999.99, 999.99); + } + break; + }; + enum { eDynamicFieldWidth = 100 }; + _dynamicFieldWidget->setSizePolicy(sizePolicy); + _dynamicFieldWidget->setFixedWidth(eDynamicFieldWidth); + _optionsPage->dynamicValueLayout->addWidget(_dynamicFieldWidget); +} + +void NotifyPluginOptionsPage::setDynamicFieldValue(NotificationItem* notification) +{ + if (QDoubleSpinBox* seValue = dynamic_cast(_dynamicFieldWidget)) + seValue->setValue(notification->singleValue().toDouble()); + else { + if (QComboBox* cbValue = dynamic_cast(_dynamicFieldWidget)) { + int idx = cbValue->findText(notification->singleValue().toString()); + if(-1 != idx) + cbValue->setCurrentIndex(idx); + } else { + if (QLineEdit* rangeValue = dynamic_cast(_dynamicFieldWidget)) { + QString str = QString("%1%2").arg(notification->singleValue().toDouble(), 5, 'f', 2, '0') + .arg(notification->valueRange2(), 5, 'f', 2, '0'); + rangeValue->setText(str); + } else { + qNotifyDebug() << "NotifyPluginOptionsPage::setDynamicValueField | unknown _fieldValue: " << _dynamicFieldWidget; + } + } + } +} + +void NotifyPluginOptionsPage::resetFieldType() +{ + _dynamicFieldType = -1; +} + +void NotifyPluginOptionsPage::getOptionsPageValues(NotificationItem* notification) +{ + Q_ASSERT(notification); + notification->setSoundCollectionPath(_optionsPage->SoundDirectoryPathChooser->path()); + notification->setCurrentLanguage(_optionsPage->SoundCollectionList->currentText()); + notification->setDataObject(_optionsPage->UAVObject->currentText()); + notification->setObjectField(_optionsPage->UAVObjectField->currentText()); + notification->setSound1(_optionsPage->Sound1->currentText()); + notification->setSound2(_optionsPage->Sound2->currentText()); + notification->setSound3(_optionsPage->Sound3->currentText()); + notification->setSayOrder(_sayOrder->currentIndex()); + notification->setCondition(NotifyPluginOptionsPage::conditionValues.indexOf(_dynamicFieldCondition->currentText())); + if (QDoubleSpinBox* spinValue = dynamic_cast(_dynamicFieldWidget)) + notification->setSingleValue(spinValue->value()); + else { + if (QComboBox* comboBoxValue = dynamic_cast(_dynamicFieldWidget)) + notification->setSingleValue(comboBoxValue->currentText()); + else { + if (QLineEdit* rangeValue = dynamic_cast(_dynamicFieldWidget)) { + QString str = rangeValue->text(); + QStringList range = str.split(':'); + notification->setSingleValue(range.at(0).toDouble()); + notification->setValueRange2(range.at(1).toDouble()); + } + } + } +} + +void NotifyPluginOptionsPage::updateConfigView(NotificationItem* notification) +{ + Q_ASSERT(notification); + disconnect(_optionsPage->UAVObject, SIGNAL(currentIndexChanged(QString)), + this, SLOT(on_changedIndex_UAVObject(QString))); + disconnect(_optionsPage->UAVObjectField, SIGNAL(currentIndexChanged(QString)), + this, SLOT(on_changedIndex_UAVField(QString))); + + QString path = notification->getSoundCollectionPath(); + if (path.isEmpty()) { + path = Utils::PathUtils().InsertDataPath("%%DATAPATH%%sounds"); + } + + _optionsPage->SoundDirectoryPathChooser->setPath(path); + + if (-1 != _optionsPage->SoundCollectionList->findText(notification->getCurrentLanguage())) { + _optionsPage->SoundCollectionList->setCurrentIndex(_optionsPage->SoundCollectionList->findText(notification->getCurrentLanguage())); + } else { + _optionsPage->SoundCollectionList->setCurrentIndex(_optionsPage->SoundCollectionList->findText("default")); + } + + // Fills the combo boxes for the UAVObjects + QList< QList > objList = _objManager.getDataObjects(); + foreach (QList list, objList) { + foreach (UAVDataObject* obj, list) { + _optionsPage->UAVObject->addItem(obj->getName()); + } + } + + if (-1 != _optionsPage->UAVObject->findText(notification->getDataObject())) { + _optionsPage->UAVObject->setCurrentIndex(_optionsPage->UAVObject->findText(notification->getDataObject())); + } + + _optionsPage->UAVObjectField->clear(); + if(_currUAVObject) { + QList fieldList = _currUAVObject->getFields(); + foreach (UAVObjectField* field, fieldList) + _optionsPage->UAVObjectField->addItem(field->getName()); + } + + if (-1 != _optionsPage->UAVObjectField->findText(notification->getObjectField())) { + _optionsPage->UAVObjectField->setCurrentIndex(_optionsPage->UAVObjectField->findText(notification->getObjectField())); + } + + if (-1 != _optionsPage->Sound1->findText(notification->getSound1())) { + _optionsPage->Sound1->setCurrentIndex(_optionsPage->Sound1->findText(notification->getSound1())); + } else { + // show item from default location + _optionsPage->SoundCollectionList->setCurrentIndex(_optionsPage->SoundCollectionList->findText("default")); + _optionsPage->Sound1->setCurrentIndex(_optionsPage->Sound1->findText(notification->getSound1())); + } + + if (-1 != _optionsPage->Sound2->findText(notification->getSound2())) { + _optionsPage->Sound2->setCurrentIndex(_optionsPage->Sound2->findText(notification->getSound2())); + } else { + // show item from default location + _optionsPage->SoundCollectionList->setCurrentIndex(_optionsPage->SoundCollectionList->findText("default")); + _optionsPage->Sound2->setCurrentIndex(_optionsPage->Sound2->findText(notification->getSound2())); + } + + if (-1 != _optionsPage->Sound3->findText(notification->getSound3())) { + _optionsPage->Sound3->setCurrentIndex(_optionsPage->Sound3->findText(notification->getSound3())); + } else { + // show item from default location + _optionsPage->SoundCollectionList->setCurrentIndex(_optionsPage->SoundCollectionList->findText("default")); + _optionsPage->Sound3->setCurrentIndex(_optionsPage->Sound3->findText(notification->getSound3())); + } + + _dynamicFieldCondition->setCurrentIndex(_dynamicFieldCondition->findText(NotifyPluginOptionsPage::conditionValues.at(notification->getCondition()))); + + _sayOrder->setCurrentIndex(notification->getSayOrder()); + + setDynamicFieldValue(notification); + + connect(_optionsPage->UAVObject, SIGNAL(currentIndexChanged(QString)), + this, SLOT(on_changedIndex_UAVObject(QString))); + connect(_optionsPage->UAVObjectField, SIGNAL(currentIndexChanged(QString)), + this, SLOT(on_changedIndex_UAVField(QString))); } -void NotifyPluginOptionsPage::changeButtonText(Phonon::State newstate, Phonon::State oldstate) +void NotifyPluginOptionsPage::on_changedIndex_rangeValue(QString /* rangeStr */) { - if(newstate == Phonon::PausedState || newstate == Phonon::StoppedState){ - options_page->buttonPlayNotification->setText("Play"); - options_page->buttonPlayNotification->setIcon(QPixmap(":/notify/images/play.png")); - } - else - if(newstate == Phonon::PlayingState) { - options_page->buttonPlayNotification->setText("Stop"); - options_page->buttonPlayNotification->setIcon(QPixmap(":/notify/images/stop.png")); - } + Q_ASSERT(_dynamicFieldWidget); + UAVObjectField* field = getObjectFieldFromSelected(); + Q_ASSERT(!!field); + addDynamicFieldWidget(field); + setDynamicFieldValue(_selectedNotification); } - -void NotifyPluginOptionsPage::on_buttonTestSoundNotification_clicked() +void NotifyPluginOptionsPage::on_changedIndex_UAVField(QString field) { - // QList messageNotify; - NotifyPluginConfiguration *notification; - - if(notifyRulesSelection->currentIndex().row()==-1) return; - - notifySound->clearQueue(); - notification = privListNotifications.at(notifyRulesSelection->currentIndex().row()); - notification->parseNotifyMessage(); - foreach(QString item, notification->getNotifyMessageList()) - notifySound->enqueue(Phonon::MediaSource(item)); - notifySound->play(); -} - -void NotifyPluginOptionsPage::on_chkEnableSound_toggled(bool state) -{ - bool state1 = 1^state; - - QList listOutputs = notifySound->outputPaths(); - Phonon::AudioOutput * audioOutput = (Phonon::AudioOutput*)listOutputs.last().sink(); - audioOutput->setMuted(state1); -} - -void NotifyPluginOptionsPage::updateConfigView(NotifyPluginConfiguration* notification) -{ - QString path = notification->getSoundCollectionPath(); - if(path=="") - { - //QDir dir = QDir::currentPath(); - //path = QDir::currentPath().left(QDir::currentPath().indexOf("OpenPilot",0,Qt::CaseSensitive))+"../share/sounds"; - path = Utils::PathUtils().InsertDataPath("%%DATAPATH%%sounds"); - } - options_page->SoundDirectoryPathChooser->setPath(path); - - if(options_page->SoundCollectionList->findText(notification->getCurrentLanguage())!=-1){ - options_page->SoundCollectionList->setCurrentIndex(options_page->SoundCollectionList->findText(notification->getCurrentLanguage())); - } - else - options_page->SoundCollectionList->setCurrentIndex(options_page->SoundCollectionList->findText("default")); - - - if(options_page->UAVObject->findText(notification->getDataObject())!=-1){ - options_page->UAVObject->setCurrentIndex(options_page->UAVObject->findText(notification->getDataObject())); - } - - // Now load the object field values: - options_page->UAVObjectField->clear(); - QString uavDataObject = notification->getDataObject(); - UAVDataObject* obj = dynamic_cast( objManager->getObject(uavDataObject/*objList.at(0).at(0)->getName()*/) ); - if (obj != NULL ) { - QList fieldList = obj->getFields(); - foreach (UAVObjectField* field, fieldList) { - options_page->UAVObjectField->addItem(field->getName()); - } - } - - if(options_page->UAVObjectField->findText(notification->getObjectField())!=-1){ - options_page->UAVObjectField->setCurrentIndex(options_page->UAVObjectField->findText(notification->getObjectField())); - } - - if(options_page->Sound1->findText(notification->getSound1())!=-1){ - options_page->Sound1->setCurrentIndex(options_page->Sound1->findText(notification->getSound1())); - } - else - { - // show item from default location - options_page->SoundCollectionList->setCurrentIndex(options_page->SoundCollectionList->findText("default")); - options_page->Sound1->setCurrentIndex(options_page->Sound1->findText(notification->getSound1())); - - // don't show item if it wasn't find in stored location - //options_page->Sound1->setCurrentIndex(-1); - } - - if(options_page->Sound2->findText(notification->getSound2())!=-1) { - options_page->Sound2->setCurrentIndex(options_page->Sound2->findText(notification->getSound2())); - } - else { - // show item from default location - options_page->SoundCollectionList->setCurrentIndex(options_page->SoundCollectionList->findText("default")); - options_page->Sound2->setCurrentIndex(options_page->Sound2->findText(notification->getSound2())); - - // don't show item if it wasn't find in stored location - //options_page->Sound2->setCurrentIndex(-1); - } - - if(options_page->Sound3->findText(notification->getSound3())!=-1) { - options_page->Sound3->setCurrentIndex(options_page->Sound3->findText(notification->getSound3())); - } - else { - // show item from default location - options_page->SoundCollectionList->setCurrentIndex(options_page->SoundCollectionList->findText("default")); - options_page->Sound3->setCurrentIndex(options_page->Sound3->findText(notification->getSound3())); - } - - if(options_page->Value->findText(notification->getValue())!=-1) { - options_page->Value->setCurrentIndex(options_page->Value->findText(notification->getValue())); - } - - if(options_page->SayOrder->findText(notification->getSayOrder())!=-1) { - options_page->SayOrder->setCurrentIndex(options_page->SayOrder->findText(notification->getSayOrder())); - } - options_page->ValueSpinBox->setValue(notification->getSpinBoxValue()); -} - -void NotifyPluginOptionsPage::on_tableNotification_changeSelection( const QItemSelection & selected, const QItemSelection & deselected ) -{ - bool select = true; - notifySound->stop(); - if(selected.indexes().size()) - updateConfigView(privListNotifications.at(selected.indexes().at(0).row())); - else - select = false; - - options_page->buttonModify->setEnabled(select); - options_page->buttonDelete->setEnabled(select); - options_page->buttonPlayNotification->setEnabled(select); -} - - - -void NotifyPluginOptionsPage::on_buttonAddNotification_clicked() -{ - NotifyPluginConfiguration* notification = new NotifyPluginConfiguration; - - if(options_page->SoundDirectoryPathChooser->path()=="") - { - QPalette textPalette=options_page->SoundDirectoryPathChooser->palette(); - textPalette.setColor(QPalette::Normal,QPalette::Text, Qt::red); - options_page->SoundDirectoryPathChooser->setPalette(textPalette); - options_page->SoundDirectoryPathChooser->setPath("please select sound collection folder"); - return; - } - - notification->setSoundCollectionPath(options_page->SoundDirectoryPathChooser->path()); - notification->setCurrentLanguage(options_page->SoundCollectionList->currentText()); - notification->setDataObject(options_page->UAVObject->currentText()); - notification->setObjectField(options_page->UAVObjectField->currentText()); - notification->setValue(options_page->Value->currentText()); - notification->setSpinBoxValue(options_page->ValueSpinBox->value()); - - if(options_page->Sound1->currentText()!="") - notification->setSound1(options_page->Sound1->currentText()); - - notification->setSound2(options_page->Sound2->currentText()); - notification->setSound3(options_page->Sound3->currentText()); - - if(((options_page->Sound2->currentText()=="")&&(options_page->SayOrder->currentText()=="After second")) - || ((options_page->Sound3->currentText()=="")&&(options_page->SayOrder->currentText()=="After third"))) - return; - else - notification->setSayOrder(options_page->SayOrder->currentText()); - - privListNotifications.append(notification); - emit entryAdded(privListNotifications.size()-1); - notifyRulesSelection->setCurrentIndex(notifyRulesModel->index(privListNotifications.size()-1,0,QModelIndex()), - QItemSelectionModel::ClearAndSelect | QItemSelectionModel::Rows); -} - - -void NotifyPluginOptionsPage::on_buttonDeleteNotification_clicked() -{ - notifyRulesModel->removeRow(notifyRulesSelection->currentIndex().row()); - if(!notifyRulesModel->rowCount() && (notifyRulesSelection->currentIndex().row() > 0 && notifyRulesSelection->currentIndex().row() < notifyRulesModel->rowCount())) - { - options_page->buttonDelete->setEnabled(false); - options_page->buttonModify->setEnabled(false); - options_page->buttonPlayNotification->setEnabled(false); - } + resetFieldType(); + Q_ASSERT(_currUAVObject); + addDynamicField(_currUAVObject->getField(field)); } -void NotifyPluginOptionsPage::on_buttonModifyNotification_clicked() +void NotifyPluginOptionsPage::on_changedIndex_UAVObject(QString val) { - NotifyPluginConfiguration* notification = new NotifyPluginConfiguration; - getOptionsPageValues(notification); - notification->setRepeatFlag(privListNotifications.at(notifyRulesSelection->currentIndex().row())->getRepeatFlag()); - privListNotifications.replace(notifyRulesSelection->currentIndex().row(),notification); - entryUpdated(notifyRulesSelection->currentIndex().row()); - + resetFieldType(); + _currUAVObject = dynamic_cast( _objManager.getObject(val) ); + if(!_currUAVObject) { + qNotifyDebug() << "on_UAVObject_indexChanged | no such UAVOBject"; + return; + } + QList fieldList = _currUAVObject->getFields(); + disconnect(_optionsPage->UAVObjectField, SIGNAL(currentIndexChanged(QString)), this, SLOT(on_changedIndex_UAVField(QString))); + _optionsPage->UAVObjectField->clear(); + foreach (UAVObjectField* field, fieldList) { + _optionsPage->UAVObjectField->addItem(field->getName()); + } + connect(_optionsPage->UAVObjectField, SIGNAL(currentIndexChanged(QString)), this, SLOT(on_changedIndex_UAVField(QString))); + _selectedNotification->setObjectField(fieldList.at(0)->getName()); + addDynamicField(fieldList.at(0)); } + +void NotifyPluginOptionsPage::on_changedIndex_soundLanguage(int index) +{ + _optionsPage->SoundCollectionList->setCurrentIndex(index); + QString collectionPath = _optionsPage->SoundDirectoryPathChooser->path() + + QDir::toNativeSeparators("/" + _optionsPage->SoundCollectionList->currentText()); + + QDir dirPath(collectionPath); + QStringList filters; + filters << "*.mp3" << "*.wav"; + dirPath.setNameFilters(filters); + QStringList listSoundFiles = dirPath.entryList(filters); + listSoundFiles.replaceInStrings(QRegExp(".mp3|.wav"), ""); + _optionsPage->Sound1->clear(); + _optionsPage->Sound2->clear(); + _optionsPage->Sound3->clear(); + _optionsPage->Sound1->addItem(""); + _optionsPage->Sound1->addItems(listSoundFiles); + _optionsPage->Sound2->addItem(""); + _optionsPage->Sound2->addItems(listSoundFiles); + _optionsPage->Sound3->addItem(""); + _optionsPage->Sound3->addItems(listSoundFiles); +} + + +void NotifyPluginOptionsPage::on_changed_playButtonText(Phonon::State newstate, Phonon::State /* oldstate */) +{ + //Q_ASSERT(Phonon::ErrorState != newstate); + + if (newstate == Phonon::PausedState || newstate == Phonon::StoppedState) { + _optionsPage->buttonPlayNotification->setText("Play"); + _optionsPage->buttonPlayNotification->setIcon(QPixmap(":/notify/images/play.png")); + } else { + if (newstate == Phonon::PlayingState) { + _optionsPage->buttonPlayNotification->setText("Stop"); + _optionsPage->buttonPlayNotification->setIcon(QPixmap(":/notify/images/stop.png")); + } + } +} + +void NotifyPluginOptionsPage::on_changedSelection_notifyTable(const QItemSelection & selected, const QItemSelection & /* deselected */ ) +{ + bool select = false; + _testSound->stop(); + if (selected.indexes().size()) { + select = true; + setSelectedNotification(_privListNotifications.at(selected.indexes().at(0).row())); + UAVObjectField* field = getObjectFieldFromSelected(); + addDynamicField(field); + updateConfigView(_selectedNotification); + } + + _optionsPage->buttonModify->setEnabled(select); + _optionsPage->buttonDelete->setEnabled(select); + _optionsPage->buttonPlayNotification->setEnabled(select); +} + +void NotifyPluginOptionsPage::on_clicked_buttonSoundFolder(const QString& path) +{ + QDir dirPath(path); + QStringList listDirCollections = dirPath.entryList(QDir::AllDirs | QDir::NoDotAndDotDot); + _optionsPage->SoundCollectionList->clear(); + _optionsPage->SoundCollectionList->addItems(listDirCollections); +} + +void NotifyPluginOptionsPage::on_clicked_buttonTestSoundNotification() +{ + NotificationItem* notification = NULL; + qNotifyDebug() << "on_buttonTestSoundNotification_clicked"; + Q_ASSERT(-1 != _notifyRulesSelection->currentIndex().row()); + _testSound->clearQueue(); + notification = _privListNotifications.at(_notifyRulesSelection->currentIndex().row()); + QStringList sequence = notification->toSoundList(); + if (sequence.isEmpty()) { + qNotifyDebug() << "message sequense is empty!"; + return; + } + foreach(QString item, sequence) { + qNotifyDebug() << item; + _testSound->enqueue(Phonon::MediaSource(item)); + } + _testSound->play(); +} + +void NotifyPluginOptionsPage::on_clicked_buttonAddNotification() +{ + NotificationItem* notification = new NotificationItem; + + if (_optionsPage->SoundDirectoryPathChooser->path().isEmpty()) { + QPalette textPalette=_optionsPage->SoundDirectoryPathChooser->palette(); + textPalette.setColor(QPalette::Normal,QPalette::Text, Qt::red); + _optionsPage->SoundDirectoryPathChooser->setPalette(textPalette); + _optionsPage->SoundDirectoryPathChooser->setPath("please select sound collection folder"); + delete notification; + return; + } + getOptionsPageValues(notification); + + if ( ((!_optionsPage->Sound2->currentText().isEmpty()) && (_sayOrder->currentText()=="After second")) + || ((!_optionsPage->Sound3->currentText().isEmpty()) && (_sayOrder->currentText()=="After third")) ) { + delete notification; + return; + } else { + notification->setSayOrder(_sayOrder->currentIndex()); + } + + _notifyRulesModel->entryAdded(notification); + _notifyRulesSelection->setCurrentIndex(_notifyRulesModel->index(_privListNotifications.size()-1,0,QModelIndex()), + QItemSelectionModel::ClearAndSelect | QItemSelectionModel::Rows); +} + +void NotifyPluginOptionsPage::on_clicked_buttonDeleteNotification() +{ + _notifyRulesModel->removeRow(_notifyRulesSelection->currentIndex().row()); + if (!_notifyRulesModel->rowCount() + && (_notifyRulesSelection->currentIndex().row() > 0 + && _notifyRulesSelection->currentIndex().row() < _notifyRulesModel->rowCount()) ) + { + _optionsPage->buttonDelete->setEnabled(false); + _optionsPage->buttonModify->setEnabled(false); + _optionsPage->buttonPlayNotification->setEnabled(false); + } +} + +void NotifyPluginOptionsPage::on_clicked_buttonModifyNotification() +{ + NotificationItem* notification = new NotificationItem; + getOptionsPageValues(notification); + notification->setRetryValue(_privListNotifications.at(_notifyRulesSelection->currentIndex().row())->retryValue()); + notification->setLifetime(_privListNotifications.at(_notifyRulesSelection->currentIndex().row())->lifetime()); + notification->setMute(_privListNotifications.at(_notifyRulesSelection->currentIndex().row())->mute()); + + _privListNotifications.replace(_notifyRulesSelection->currentIndex().row(),notification); + entryUpdated(_notifyRulesSelection->currentIndex().row()); +} + +void NotifyPluginOptionsPage::on_FinishedPlaying() +{ + _testSound->clear(); +} + +void NotifyPluginOptionsPage::on_toggled_checkEnableSound(bool state) +{ + bool state1 = 1^state; + + QList listOutputs = _testSound->outputPaths(); + Phonon::AudioOutput * audioOutput = (Phonon::AudioOutput*)listOutputs.last().sink(); + audioOutput->setMuted(state1); +} diff --git a/ground/openpilotgcs/src/plugins/notify/notifypluginoptionspage.cpp.orig b/ground/openpilotgcs/src/plugins/notify/notifypluginoptionspage.cpp.orig new file mode 100644 index 000000000..2ff775e31 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/notify/notifypluginoptionspage.cpp.orig @@ -0,0 +1,512 @@ +/** + ****************************************************************************** + * + * @file notifypluginoptionspage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Notify Plugin options page + * @see The GNU Public License (GPL) Version 3 + * @defgroup notifyplugin + * @{ + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "notifypluginoptionspage.h" +#include +#include "notificationitem.h" +#include "ui_notifypluginoptionspage.h" +#include "extensionsystem/pluginmanager.h" +#include "utils/pathutils.h" + +#include +#include +#include +#include +#include +#include +#include + +#include "notifyplugin.h" +#include "notifyitemdelegate.h" +#include "notifytablemodel.h" +#include "notifylogging.h" + +NotifyPluginOptionsPage::NotifyPluginOptionsPage(/*NotificationItem *config,*/ QObject *parent) + : IOptionsPage(parent) + , objManager(*ExtensionSystem::PluginManager::instance()->getObject()) + , owner(qobject_cast(parent)) + , currentCollectionPath("") +{ +} + +NotifyPluginOptionsPage::~NotifyPluginOptionsPage() +{ +} + +//creates options page widget (uses the UI file) +QWidget *NotifyPluginOptionsPage::createPage(QWidget *parent) +{ + options_page.reset(new Ui::NotifyPluginOptionsPage()); + //main widget + QWidget *optionsPageWidget = new QWidget; + //main layout + options_page->setupUi(optionsPageWidget); + + listSoundFiles.clear(); + + options_page->SoundDirectoryPathChooser->setExpectedKind(Utils::PathChooser::Directory); + options_page->SoundDirectoryPathChooser->setPromptDialogTitle(tr("Choose sound collection directory")); + + // Fills the combo boxes for the UAVObjects + QList< QList > objList = objManager.getDataObjects(); + foreach (QList list, objList) { + foreach (UAVDataObject* obj, list) { + options_page->UAVObject->addItem(obj->getName()); + } + } + +<<<<<<< Updated upstream + connect(options_page->SoundDirectoryPathChooser, SIGNAL(changed(const QString&)), this, SLOT(on_buttonSoundFolder_clicked(const QString&))); + connect(options_page->SoundCollectionList, SIGNAL(currentIndexChanged (int)), this, SLOT(on_soundLanguage_indexChanged(int))); + connect(options_page->UAVObject, SIGNAL(currentIndexChanged(QString)), this, SLOT(on_UAVObject_indexChanged(QString))); +======= + options_page = new Ui::NotifyPluginOptionsPage(); + //main widget + QWidget *optionsPageWidget = new QWidget; + //main layout + options_page->setupUi(optionsPageWidget); + + delegateItems.clear(); + listSoundFiles.clear(); + + options_page->horizontalLayout_3->addWidget(new QPushButton("testtt")); + delegateItems << "Repeat Once" + << "Repeat Instantly" + << "Repeat 10 seconds" + << "Repeat 30 seconds" + << "Repeat 1 minute"; + + options_page->chkEnableSound->setChecked(owner->getEnableSound()); + options_page->SoundDirectoryPathChooser->setExpectedKind(Utils::PathChooser::Directory); + options_page->SoundDirectoryPathChooser->setPromptDialogTitle(tr("Choose sound collection directory")); + + + + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + objManager = pm->getObject(); + + // Fills the combo boxes for the UAVObjects + QList< QList > objList = objManager->getDataObjects(); + foreach (QList list, objList) { + foreach (UAVDataObject* obj, list) { + options_page->UAVObject->addItem(obj->getName()); + } + } + + connect(options_page->SoundDirectoryPathChooser, SIGNAL(changed(const QString&)), this, SLOT(on_buttonSoundFolder_clicked(const QString&))); + connect(options_page->SoundCollectionList, SIGNAL(currentIndexChanged (int)), this, SLOT(on_soundLanguage_indexChanged(int))); + connect(options_page->buttonAdd, SIGNAL(pressed()), this, SLOT(on_buttonAddNotification_clicked())); + connect(options_page->buttonDelete, SIGNAL(pressed()), this, SLOT(on_buttonDeleteNotification_clicked())); + connect(options_page->buttonModify, SIGNAL(pressed()), this, SLOT(on_buttonModifyNotification_clicked())); +// connect(options_page->buttonTestSound1, SIGNAL(clicked()), this, SLOT(on_buttonTestSound1_clicked())); +// connect(options_page->buttonTestSound2, SIGNAL(clicked()), this, SLOT(on_buttonTestSound2_clicked())); + connect(options_page->buttonPlayNotification, SIGNAL(clicked()), this, SLOT(on_buttonTestSoundNotification_clicked())); + connect(options_page->chkEnableSound, SIGNAL(toggled(bool)), this, SLOT(on_chkEnableSound_toggled(bool))); + + + connect(options_page->UAVObject, SIGNAL(currentIndexChanged(QString)), this, SLOT(on_UAVObject_indexChanged(QString))); + connect(this, SIGNAL(updateNotifications(QList)), + owner, SLOT(updateNotificationList(QList))); + connect(this, SIGNAL(resetNotification()),owner, SLOT(resetNotification())); + + //emit resetNotification(); + + + privListNotifications.clear(); + + for (int i = 0; i < owner->getListNotifications().size(); ++i) { + NotifyPluginConfiguration* notification = new NotifyPluginConfiguration(); + owner->getListNotifications().at(i)->copyTo(notification); + privListNotifications.append(notification); + } + + updateConfigView(owner->getCurrentNotification()); + + options_page->chkEnableSound->setChecked(owner->getEnableSound()); + + QStringList headerStrings; + headerStrings << "Name" << "Repeats" << "Lifetime,sec"; +>>>>>>> Stashed changes + + connect(this, SIGNAL(updateNotifications(QList)), + owner, SLOT(updateNotificationList(QList))); + //connect(this, SIGNAL(resetNotification()),owner, SLOT(resetNotification())); + + +// privListNotifications = ((qobject_cast(parent))->getListNotifications()); + privListNotifications = owner->getListNotifications(); + + updateConfigView(owner->getCurrentNotification()); + + initRulesTable(); + initButtons(); + initPhononPlayer(); + + return optionsPageWidget; +} + +void NotifyPluginOptionsPage::initButtons() +{ + options_page->chkEnableSound->setChecked(owner->getEnableSound()); + connect(options_page->chkEnableSound, SIGNAL(toggled(bool)), this, SLOT(on_chkEnableSound_toggled(bool))); + + options_page->buttonModify->setEnabled(false); + options_page->buttonDelete->setEnabled(false); + options_page->buttonPlayNotification->setEnabled(false); + connect(options_page->buttonAdd, SIGNAL(pressed()), this, SLOT(on_buttonAddNotification_clicked())); + connect(options_page->buttonDelete, SIGNAL(pressed()), this, SLOT(on_buttonDeleteNotification_clicked())); + connect(options_page->buttonModify, SIGNAL(pressed()), this, SLOT(on_buttonModifyNotification_clicked())); + connect(options_page->buttonPlayNotification, SIGNAL(clicked()), this, SLOT(on_buttonTestSoundNotification_clicked())); +} + +void NotifyPluginOptionsPage::initPhononPlayer() +{ + notifySound.reset(Phonon::createPlayer(Phonon::NotificationCategory)); + connect(notifySound.data(),SIGNAL(stateChanged(Phonon::State,Phonon::State)), + this,SLOT(changeButtonText(Phonon::State,Phonon::State))); + connect(notifySound.data(), SIGNAL(finished(void)), this, SLOT(onFinishedPlaying(void))); +} + +void NotifyPluginOptionsPage::initRulesTable() +{ + qNotifyDebug_if(_notifyRulesModel.isNull()) << "_notifyRulesModel.isNull())"; + qNotifyDebug_if(!_notifyRulesSelection) << "_notifyRulesSelection.isNull())"; + //QItemSelectionModel* selection = _notifyRulesSelection.take(); + _notifyRulesModel.reset(new NotifyTableModel(privListNotifications)); + _notifyRulesSelection = new QItemSelectionModel(_notifyRulesModel.data()); + + connect(_notifyRulesSelection, SIGNAL(selectionChanged ( const QItemSelection &, const QItemSelection & )), + this, SLOT(on_tableNotification_changeSelection( const QItemSelection & , const QItemSelection & ))); + connect(this, SIGNAL(entryUpdated(int)), + _notifyRulesModel.data(), SLOT(entryUpdated(int))); + connect(this, SIGNAL(entryAdded(int)), + _notifyRulesModel.data(), SLOT(entryAdded(int))); + + options_page->notifyRulesView->setModel(_notifyRulesModel.data()); + options_page->notifyRulesView->setSelectionModel(_notifyRulesSelection); + options_page->notifyRulesView->setItemDelegate(new NotifyItemDelegate(this)); + + options_page->notifyRulesView->resizeRowsToContents(); + options_page->notifyRulesView->setColumnWidth(eMESSAGE_NAME,200); + options_page->notifyRulesView->setColumnWidth(eREPEAT_VALUE,120); + options_page->notifyRulesView->setColumnWidth(eEXPIRE_TIME,100); + options_page->notifyRulesView->setColumnWidth(eENABLE_NOTIFICATION,60); + options_page->notifyRulesView->setDragEnabled(true); + options_page->notifyRulesView->setAcceptDrops(true); + options_page->notifyRulesView->setDropIndicatorShown(true); + options_page->notifyRulesView->setDragDropMode(QAbstractItemView::InternalMove); + + +} + +void NotifyPluginOptionsPage::getOptionsPageValues(NotificationItem* notification) +{ + notification->setSoundCollectionPath(options_page->SoundDirectoryPathChooser->path()); + notification->setCurrentLanguage(options_page->SoundCollectionList->currentText()); + notification->setDataObject(options_page->UAVObject->currentText()); + notification->setObjectField(options_page->UAVObjectField->currentText()); + notification->setSound1(options_page->Sound1->currentText()); + notification->setSound2(options_page->Sound2->currentText()); + notification->setSound3(options_page->Sound3->currentText()); + notification->setSayOrder(options_page->SayOrder->currentText()); + notification->setValue(options_page->Value->currentText()); + notification->setSpinBoxValue(options_page->ValueSpinBox->value()); +} + +/*! +* Called when the user presses apply or OK. +* Saves the current values +*/ +void NotifyPluginOptionsPage::apply() +{ + getOptionsPageValues(owner->getCurrentNotification()); + owner->setEnableSound(options_page->chkEnableSound->isChecked()); + emit updateNotifications(privListNotifications); +} + +void NotifyPluginOptionsPage::finish() +{ + disconnect(notifySound.data(),SIGNAL(stateChanged(Phonon::State,Phonon::State)), + this,SLOT(changeButtonText(Phonon::State,Phonon::State))); + if (notifySound) { + notifySound->stop(); + notifySound->clear(); + } +} + +////////////////////////////////////////////////////////////////////////////// +// Fills in the combo box when value is changed in the +// combo box +////////////////////////////////////////////////////////////////////////////// +void NotifyPluginOptionsPage::on_UAVObject_indexChanged(QString val) { + options_page->UAVObjectField->clear(); + ExtensionSystem::PluginManager* pm = ExtensionSystem::PluginManager::instance(); + UAVObjectManager* objManager = pm->getObject(); + UAVDataObject* obj = dynamic_cast( objManager->getObject(val) ); + QList fieldList = obj->getFields(); + foreach (UAVObjectField* field, fieldList) { + options_page->UAVObjectField->addItem(field->getName()); + } +} + +// locate collection folder on disk +void NotifyPluginOptionsPage::on_buttonSoundFolder_clicked(const QString& path) +{ + QDir dirPath(path); + listDirCollections = dirPath.entryList(QDir::AllDirs | QDir::NoDotAndDotDot); + options_page->SoundCollectionList->clear(); + options_page->SoundCollectionList->addItems(listDirCollections); +} + + +void NotifyPluginOptionsPage::on_soundLanguage_indexChanged(int index) +{ + options_page->SoundCollectionList->setCurrentIndex(index); + + currentCollectionPath = options_page->SoundDirectoryPathChooser->path() + + QDir::toNativeSeparators("/" + options_page->SoundCollectionList->currentText()); + + QDir dirPath(currentCollectionPath); + QStringList filters; + filters << "*.mp3" << "*.wav"; + dirPath.setNameFilters(filters); + listSoundFiles = dirPath.entryList(filters); + listSoundFiles.replaceInStrings(QRegExp(".mp3|.wav"), ""); + options_page->Sound1->clear(); + options_page->Sound2->clear(); + options_page->Sound3->clear(); + options_page->Sound1->addItems(listSoundFiles); + options_page->Sound2->addItem(""); + options_page->Sound2->addItems(listSoundFiles); + options_page->Sound3->addItem(""); + options_page->Sound3->addItems(listSoundFiles); + +} + +void NotifyPluginOptionsPage::changeButtonText(Phonon::State newstate, Phonon::State oldstate) +{ + //Q_ASSERT(Phonon::ErrorState != newstate); + + if (newstate == Phonon::PausedState || newstate == Phonon::StoppedState) { + options_page->buttonPlayNotification->setText("Play"); + options_page->buttonPlayNotification->setIcon(QPixmap(":/notify/images/play.png")); + } else { + if (newstate == Phonon::PlayingState) { + options_page->buttonPlayNotification->setText("Stop"); + options_page->buttonPlayNotification->setIcon(QPixmap(":/notify/images/stop.png")); + } + } +} + +void NotifyPluginOptionsPage::onFinishedPlaying() +{ + notifySound->clear(); +} + +void NotifyPluginOptionsPage::on_buttonTestSoundNotification_clicked() +{ + NotificationItem* notification = NULL; + + if (-1 == _notifyRulesSelection->currentIndex().row()) + return; + notifySound->clearQueue(); + notification = privListNotifications.at(_notifyRulesSelection->currentIndex().row()); + notification->parseNotifyMessage(); + QStringList sequence = notification->getMessageSequence(); + Q_ASSERT(!!sequence.size()); + foreach(QString item, sequence) + notifySound->enqueue(Phonon::MediaSource(item)); + + notifySound->play(); +} + +void NotifyPluginOptionsPage::on_chkEnableSound_toggled(bool state) +{ + bool state1 = 1^state; + + QList listOutputs = notifySound->outputPaths(); + Phonon::AudioOutput * audioOutput = (Phonon::AudioOutput*)listOutputs.last().sink(); + audioOutput->setMuted(state1); +} + +void NotifyPluginOptionsPage::updateConfigView(NotificationItem* notification) +{ + QString path = notification->getSoundCollectionPath(); + if (path == "") { + //QDir dir = QDir::currentPath(); + //path = QDir::currentPath().left(QDir::currentPath().indexOf("OpenPilot",0,Qt::CaseSensitive))+"../share/sounds"; + path = Utils::PathUtils().InsertDataPath("%%DATAPATH%%sounds"); + } + + options_page->SoundDirectoryPathChooser->setPath(path); + + if (-1 != options_page->SoundCollectionList->findText(notification->getCurrentLanguage())){ + options_page->SoundCollectionList->setCurrentIndex(options_page->SoundCollectionList->findText(notification->getCurrentLanguage())); + } else { + options_page->SoundCollectionList->setCurrentIndex(options_page->SoundCollectionList->findText("default")); + } + + if (options_page->UAVObject->findText(notification->getDataObject())!=-1){ + options_page->UAVObject->setCurrentIndex(options_page->UAVObject->findText(notification->getDataObject())); + } + + // Now load the object field values: + options_page->UAVObjectField->clear(); + QString uavDataObject = notification->getDataObject(); + UAVDataObject* obj = dynamic_cast(objManager.getObject(uavDataObject)); + if (obj != NULL ) { + QList fieldList = obj->getFields(); + foreach (UAVObjectField* field, fieldList) { + options_page->UAVObjectField->addItem(field->getName()); + } + } + + if (-1 != options_page->UAVObjectField->findText(notification->getObjectField())) { + options_page->UAVObjectField->setCurrentIndex(options_page->UAVObjectField->findText(notification->getObjectField())); + } + + if (-1 != options_page->Sound1->findText(notification->getSound1())) { + options_page->Sound1->setCurrentIndex(options_page->Sound1->findText(notification->getSound1())); + } else { + // show item from default location + options_page->SoundCollectionList->setCurrentIndex(options_page->SoundCollectionList->findText("default")); + options_page->Sound1->setCurrentIndex(options_page->Sound1->findText(notification->getSound1())); + + // don't show item if it wasn't find in stored location + //options_page->Sound1->setCurrentIndex(-1); + } + + if (-1 != options_page->Sound2->findText(notification->getSound2())) { + options_page->Sound2->setCurrentIndex(options_page->Sound2->findText(notification->getSound2())); + } else { + // show item from default location + options_page->SoundCollectionList->setCurrentIndex(options_page->SoundCollectionList->findText("default")); + options_page->Sound2->setCurrentIndex(options_page->Sound2->findText(notification->getSound2())); + + // don't show item if it wasn't find in stored location + //options_page->Sound2->setCurrentIndex(-1); + } + + if (-1 != options_page->Sound3->findText(notification->getSound3())) { + options_page->Sound3->setCurrentIndex(options_page->Sound3->findText(notification->getSound3())); + } else { + // show item from default location + options_page->SoundCollectionList->setCurrentIndex(options_page->SoundCollectionList->findText("default")); + options_page->Sound3->setCurrentIndex(options_page->Sound3->findText(notification->getSound3())); + } + + if (-1 != options_page->Value->findText(notification->getValue())) { + options_page->Value->setCurrentIndex(options_page->Value->findText(notification->getValue())); + } + + if (-1 != options_page->SayOrder->findText(notification->getSayOrder())) { + options_page->SayOrder->setCurrentIndex(options_page->SayOrder->findText(notification->getSayOrder())); + } + + options_page->ValueSpinBox->setValue(notification->getSpinBoxValue()); +} + +void NotifyPluginOptionsPage::on_tableNotification_changeSelection( const QItemSelection & selected, const QItemSelection & deselected ) +{ + bool select = false; + notifySound->stop(); + if (selected.indexes().size()) { + select = true; + updateConfigView(privListNotifications.at(selected.indexes().at(0).row())); + } + + options_page->buttonModify->setEnabled(select); + options_page->buttonDelete->setEnabled(select); + options_page->buttonPlayNotification->setEnabled(select); +} + + +void NotifyPluginOptionsPage::on_buttonAddNotification_clicked() +{ + NotificationItem* notification = new NotificationItem; + + if (options_page->SoundDirectoryPathChooser->path()=="") { + QPalette textPalette=options_page->SoundDirectoryPathChooser->palette(); + textPalette.setColor(QPalette::Normal,QPalette::Text, Qt::red); + options_page->SoundDirectoryPathChooser->setPalette(textPalette); + options_page->SoundDirectoryPathChooser->setPath("please select sound collection folder"); + return; + } + + notification->setSoundCollectionPath(options_page->SoundDirectoryPathChooser->path()); + notification->setCurrentLanguage(options_page->SoundCollectionList->currentText()); + notification->setDataObject(options_page->UAVObject->currentText()); + notification->setObjectField(options_page->UAVObjectField->currentText()); + notification->setValue(options_page->Value->currentText()); + notification->setSpinBoxValue(options_page->ValueSpinBox->value()); + + if (options_page->Sound1->currentText().size() > 0) + notification->setSound1(options_page->Sound1->currentText()); + + notification->setSound2(options_page->Sound2->currentText()); + notification->setSound3(options_page->Sound3->currentText()); + +if ( ((!options_page->Sound2->currentText().size()) && (options_page->SayOrder->currentText()=="After second")) + || ((!options_page->Sound3->currentText().size()) && (options_page->SayOrder->currentText()=="After third")) ) { + return; + } else { + notification->setSayOrder(options_page->SayOrder->currentText()); + } + privListNotifications.append(notification); + emit entryAdded(privListNotifications.size() - 1); + _notifyRulesSelection->setCurrentIndex(_notifyRulesModel->index(privListNotifications.size()-1,0,QModelIndex()), + QItemSelectionModel::ClearAndSelect | QItemSelectionModel::Rows); +} + + +void NotifyPluginOptionsPage::on_buttonDeleteNotification_clicked() +{ + _notifyRulesModel->removeRow(_notifyRulesSelection->currentIndex().row()); + if (!_notifyRulesModel->rowCount() + && (_notifyRulesSelection->currentIndex().row() > 0 + && _notifyRulesSelection->currentIndex().row() < _notifyRulesModel->rowCount()) ) + { + options_page->buttonDelete->setEnabled(false); + options_page->buttonModify->setEnabled(false); + options_page->buttonPlayNotification->setEnabled(false); + } + +} + +void NotifyPluginOptionsPage::on_buttonModifyNotification_clicked() +{ + NotificationItem* notification = new NotificationItem; + getOptionsPageValues(notification); + notification->setRetryString(privListNotifications.at(_notifyRulesSelection->currentIndex().row())->retryString()); + notification->setLifetime(privListNotifications.at(_notifyRulesSelection->currentIndex().row())->lifetime()); + notification->setMute(privListNotifications.at(_notifyRulesSelection->currentIndex().row())->mute()); + + privListNotifications.replace(_notifyRulesSelection->currentIndex().row(),notification); + entryUpdated(_notifyRulesSelection->currentIndex().row()); + +} + diff --git a/ground/openpilotgcs/src/plugins/notify/notifypluginoptionspage.h b/ground/openpilotgcs/src/plugins/notify/notifypluginoptionspage.h index 9d159e2a4..fb3c2885d 100644 --- a/ground/openpilotgcs/src/plugins/notify/notifypluginoptionspage.h +++ b/ground/openpilotgcs/src/plugins/notify/notifypluginoptionspage.h @@ -42,83 +42,146 @@ #include #include #include +#include +#include class NotifyTableModel; - -class NotifyPluginConfiguration; +class NotificationItem; class SoundNotifyPlugin; namespace Ui { - class NotifyPluginOptionsPage; -} - + class NotifyPluginOptionsPage; +}; using namespace Core; class NotifyPluginOptionsPage : public IOptionsPage { - Q_OBJECT + Q_OBJECT + public: - explicit NotifyPluginOptionsPage(/*NotifyPluginConfiguration *config, */QObject *parent = 0); - - QString id() const { return QLatin1String("settings"); } - QString trName() const { return tr("settings"); } - QString category() const { return QLatin1String("Notify Plugin");} - QString trCategory() const { return tr("Notify Plugin");} - - + enum {equal,bigger,smaller,inrange}; + explicit NotifyPluginOptionsPage(QObject *parent = 0); + ~NotifyPluginOptionsPage(); + QString id() const { return QLatin1String("settings"); } + QString trName() const { return tr("settings"); } + QString category() const { return QLatin1String("Notify Plugin");} + QString trCategory() const { return tr("Notify Plugin");} QWidget *createPage(QWidget *parent); void apply(); - void finish(); - void restoreFromSettings(); - - void updateConfigView(NotifyPluginConfiguration* notification); - void getOptionsPageValues(NotifyPluginConfiguration* notification); - -private: - UAVObjectManager *objManager; - SoundNotifyPlugin* owner; - QStringList listDirCollections; - QStringList listSoundFiles; - QString currentCollectionPath; - int sizeNotifyList; - Phonon::MediaObject *sound1; - Phonon::MediaObject *sound2; - Phonon::MediaObject *notifySound; - Phonon::AudioOutput *audioOutput; - QStringList delegateItems; - NotifyTableModel* notifyRulesModel; - QItemSelectionModel *notifyRulesSelection; - QList privListNotifications; - - Ui::NotifyPluginOptionsPage *options_page; - //NotifyPluginConfiguration *notify; + void finish(); + void restoreFromSettings(); + static QStringList conditionValues; signals: - void updateNotifications(QList list); - void resetNotification(void); - void entryUpdated(int index); - void entryAdded(int position); - + void updateNotifications(QList list); + void entryUpdated(int index); private slots: - void showPersistentComboBox( const QModelIndex & parent, int start, int end ); - void showPersistentComboBox2 ( const QModelIndex & topLeft, const QModelIndex & bottomRight ); + void on_clicked_buttonTestSoundNotification(); + void on_clicked_buttonAddNotification(); + void on_clicked_buttonDeleteNotification(); + void on_clicked_buttonModifyNotification(); -// void on_buttonTestSound1_clicked(); -// void on_buttonTestSound2_clicked(); - void on_buttonTestSoundNotification_clicked(); + /** + * We can use continuous selection, to select simultaneously + * multiple rows to move them(using drag & drop) inside table ranges. + */ + void on_changedSelection_notifyTable( const QItemSelection & selected, const QItemSelection & deselected ); + + void on_changedIndex_soundLanguage(int index); + void on_clicked_buttonSoundFolder(const QString& path); + void on_changedIndex_UAVObject(QString val); + void on_changedIndex_UAVField(QString val); + void on_changed_playButtonText(Phonon::State newstate, Phonon::State oldstate); + void on_toggled_checkEnableSound(bool state); + + /** + * Important when we change to or from "In range" value + * For enums UI layout stayed the same, but for numeric values + * we need to change UI to show edit line, + * to have possibility assign range limits for value. + */ + void on_changedIndex_rangeValue(QString); + + void on_FinishedPlaying(void); + + +private: + Q_DISABLE_COPY(NotifyPluginOptionsPage) + + void initButtons(); + void initPhononPlayer(); + void initRulesTable(); + + void setSelectedNotification(NotificationItem* ntf); + void resetValueRange(); + void resetFieldType(); + + void updateConfigView(NotificationItem* notification); + void getOptionsPageValues(NotificationItem* notification); + UAVObjectField* getObjectFieldFromPage(); + UAVObjectField* getObjectFieldFromSelected(); + + void addDynamicFieldLayout(); + void addDynamicField(UAVObjectField* objField); + void addDynamicFieldWidget(UAVObjectField* objField); + void setDynamicFieldValue(NotificationItem* notification); + +private: + + UAVObjectManager& _objManager; + SoundNotifyPlugin* _owner; + + //! Media object uses to test sound playing + QScopedPointer _testSound; + + QScopedPointer _notifyRulesModel; + QItemSelectionModel* _notifyRulesSelection; + + /** + * Local copy of notification list, which owned by notify plugin. + * Notification list readed once on application loaded, during + * notify plugin startup, then on open options page. + * This copy is simple assignment, but due to implicitly sharing + * we don't have additional cost for that, copy will created + * only after modification of private notify list. + */ + QList _privListNotifications; + + QScopedPointer _optionsPage; + + //! Widget to convinient selection of condition for field value (equal, lower, greater) + QComboBox* _dynamicFieldCondition; + + //! Represents edit widget for dynamic UAVObjectfield, + //! can be spinbox - for numerics, combobox - enums, or + //! lineedit - for numerics with range constraints + QWidget* _dynamicFieldWidget; + + //! Type of UAVObjectField - numeric or ENUM, + //! this variable needs to correctly set appropriate dynamic UI element (_dynamicFieldWidget) + //! NOTE: ocassionaly it should be invalidated (= -1) to reset _dynamicFieldWidget + int _dynamicFieldType; + + //! Widget to convinient selection of position of + //! between sounds[1..3] + QComboBox* _sayOrder; + + //! Actualy reference to optionsPageWidget, + //! we MUST hold it beyond the scope of createPage func + //! to have possibility change dynamic parts of options page layout in future + QWidget* _form; + + //! Currently selected notification, all controls filled accroding to it. + //! On options page startup, always points to first row. + NotificationItem* _selectedNotification; + + //! Retrieved from UAVObjectManager by name from _selectedNotification, + //! if UAVObjectManager doesn't have such object, this field will be NULL + UAVDataObject* _currUAVObject; - void on_buttonAddNotification_clicked(); - void on_buttonDeleteNotification_clicked(); - void on_buttonModifyNotification_clicked(); - void on_tableNotification_changeSelection( const QItemSelection & selected, const QItemSelection & deselected ); - void on_soundLanguage_indexChanged(int index); - void on_buttonSoundFolder_clicked(const QString& path); - void on_UAVObject_indexChanged(QString val); - void changeButtonText(Phonon::State newstate, Phonon::State oldstate); - void on_chkEnableSound_toggled(bool state); }; #endif // NOTIFYPLUGINOPTIONSPAGE_H diff --git a/ground/openpilotgcs/src/plugins/notify/notifypluginoptionspage.ui b/ground/openpilotgcs/src/plugins/notify/notifypluginoptionspage.ui index b3f48432a..94560ff1a 100644 --- a/ground/openpilotgcs/src/plugins/notify/notifypluginoptionspage.ui +++ b/ground/openpilotgcs/src/plugins/notify/notifypluginoptionspage.ui @@ -6,7 +6,7 @@ 0 0 - 589 + 570 453 @@ -19,531 +19,364 @@ Form - - - - 10 - 10 - 501 - 81 - + + + QLayout::SetMinimumSize - - Sound Collection - - - - - 10 - 20 - 481 - 51 - - - - - 6 + + + + QLayout::SetFixedSize - - - - Language + + + + + 0 + 0 + - - - - - - true + + Sound Collection - - - 75 - 23 - - - - - - - - - 147 - 0 - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> + + + + + true + + + + 75 + 23 + + + + + 550 + 16777215 + + + + + + + + + 0 + 0 + + + + Language + + + + + + + + 147 + 0 + + + + <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> <html><head><meta name="qrichtext" content="1" /><style type="text/css"> p, li { white-space: pre-wrap; } </style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:8pt;">Select the sound collection</span></p></body></html> + + + + + + + + + + + + + + + + + DataObject + + + + + + + + 0 + 0 + + + + + + + + ObjectField + + + + + + + + 0 + 0 + - - - - - - 10 - 220 - 501 - 211 - - - - Sound Notifications - - - - - 10 - 180 - 481 - 26 - - - + + + + + Qt::Horizontal + + + + + + + + - + + + + 0 + 0 + + - Enable Sounds + Sound1: - - - Qt::Horizontal + + + + 0 + 0 + - + - 138 - 20 + 110 + 0 - - - - - - Play - - - - :/notify/images/play.png:/notify/images/play.png - - - - - - - Qt::Horizontal - - + - 40 - 20 + 16777215 + 16777215 - + - - - Qt::Horizontal + + + + 0 + 0 + - + + Sound2: + + + + + + + + 0 + 0 + + + - 40 - 20 + 110 + 0 - - - - - - Add - - - - :/notify/images/add.png:/notify/images/add.png + + + 16777215 + 16777215 + - - - Modify + + + + 0 + 0 + - - - :/notify/images/modify.png:/notify/images/modify.png + + Sound3: - - - Delete + + + + 0 + 0 + - - - :/utils/images/removesubmitfield.png:/utils/images/removesubmitfield.png + + + 110 + 0 + + + + + 16777215 + 16777215 + - - - - - 10 - 20 - 481 - 151 - - - - QAbstractItemView::SingleSelection - - - QAbstractItemView::SelectRows - - - 22 - - - 22 - - - - - - - 10 - 100 - 501 - 31 - - - - - - - DataObject - - - - - - - - 0 - 0 - - - - - - - - ObjectField - - - - - - - - 0 - 0 - - - - - - - - - - 7 - 130 - 501 - 20 - - - - Qt::Horizontal - - - - - - 10 - 180 - 501 - 31 - - - - - - - - 0 - 0 - - - - Sound1: - - - - - - - - 0 - 0 - - - - - 110 - 0 - - - - - 16777215 - 16777215 - - - - - - - - Sound2: - - - - - - - - 0 - 0 - - - - - 110 - 0 - - - - - 16777215 - 16777215 - - - - - - - - Sound3: - - - - - - - - 0 - 0 - - - - - 110 - 0 - - - - - 16777215 - 16777215 - - - - - - - - - - 10 - 150 - 501 - 31 - - - - - - - true - - - - 0 - 0 - - - - - 40 - 0 - - - - Value is - - - - - - - - 0 - 0 - - - - - 0 - 0 - - - - - 110 - 16777215 - - + + + + + + + + Sound Notifications + + - - Equal to - + + + QAbstractItemView::ContiguousSelection + + + QAbstractItemView::SelectRows + + + 22 + + + 22 + + - - Greater than - + + + + + Enable Sounds + + + + + + + Qt::Horizontal + + + + 138 + 20 + + + + + + + + Play + + + + :/notify/images/play.png:/notify/images/play.png + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Add + + + + :/notify/images/add.png:/notify/images/add.png + + + + + + + Modify + + + + :/notify/images/modify.png:/notify/images/modify.png + + + + + + + Delete + + + + :/utils/images/removesubmitfield.png:/utils/images/removesubmitfield.png + + + + - - - Less than - - - - - - - - - 0 - 0 - - - - - 0 - 0 - - - - - 170 - 16777215 - - - - 2 - - - 9999.899999999999636 - - - 1.000000000000000 - - - - - - - - 0 - 0 - - - - Say Order - - - - - - - - 0 - 0 - - - - - 110 - 16777215 - - - - Select if the value of the object should be spoken and if so, either before the configured sound or after it. - - - - Never - - - - - Before first - - - - - After first - - - - - After second - - - - - After third - - - - - - + + + + diff --git a/ground/openpilotgcs/src/plugins/notify/notifytablemodel.cpp b/ground/openpilotgcs/src/plugins/notify/notifytablemodel.cpp index 6f0584d70..d4913ed97 100644 --- a/ground/openpilotgcs/src/plugins/notify/notifytablemodel.cpp +++ b/ground/openpilotgcs/src/plugins/notify/notifytablemodel.cpp @@ -26,110 +26,239 @@ */ #include "notifytablemodel.h" +#include "notifylogging.h" +#include +#include + +const char* mime_type_notify_table = "openpilot/notify_plugin_table"; + +NotifyTableModel::NotifyTableModel(QList& parentList, QObject* parent) + : QAbstractTableModel(parent) + , _list(parentList) +{ + _headerStrings << "Name" << "Repeats" << "Lifetime,sec" << "Mute"; + connect(this, SIGNAL(dragRows(int, int)), this, SLOT(dropRows(int, int))); +} + bool NotifyTableModel::setData(const QModelIndex &index, const QVariant &value, int role) { - if (index.isValid() && role == Qt::EditRole) { - if(index.column()==1) - _list->at(index.row())->setRepeatFlag(value.toString()); - else - if(index.column()==2) - _list->at(index.row())->setExpireTimeout(value.toInt()); - - emit dataChanged(index, index); - return true; - } - return false; + if (index.isValid() && role == Qt::DisplayRole) { + if (eMessageName == index.column()) { + emit dataChanged(index, index); + return true; + } + } + if (index.isValid() && role == Qt::EditRole) { + if (eRepeatValue == index.column()) + _list.at(index.row())->setRetryValue(NotificationItem::retryValues.indexOf(value.toString())); + else { + if (eExpireTimer == index.column()) + _list.at(index.row())->setLifetime(value.toInt()); + else { + if (eTurnOn == index.column()) + _list.at(index.row())->setMute(value.toBool()); + } + } + emit dataChanged(index, index); + return true; + } + return false; } QVariant NotifyTableModel::data(const QModelIndex &index, int role) const { + if (!index.isValid()) { + qWarning() << "NotifyTableModel::data - index.isValid()"; + return QVariant(); + } - if (!index.isValid()) - return QVariant(); + if (index.row() >= _list.size()) + return QVariant(); - if (index.row() >= _list->size()) - return QVariant(); + if (role == Qt::DisplayRole || role == Qt::EditRole) + { + switch(index.column()) + { + case eMessageName: + return _list.at(index.row())->toString(); - if (role == Qt::DisplayRole || role == Qt::EditRole) - { - switch(index.column()) - { - case 0: - return _list->at(index.row())->parseNotifyMessage(); + case eRepeatValue: + return (NotificationItem::retryValues.at(_list.at(index.row())->retryValue())); - case 1: - return _list->at(index.row())->getRepeatFlag(); + case eExpireTimer: + return _list.at(index.row())->lifetime(); - case 2: - return _list->at(index.row())->getExpireTimeout(); + case eTurnOn: + return _list.at(index.row())->mute(); - default: - return QVariant(); - } - } - else - { - if (Qt::SizeHintRole == role){ - //QVariant size = data(index, Qt::SizeHintRole); - return QVariant(10); - } - // if(role == Qt::DecorationRole) - // if (index.column() == 0) - // return defectsIcons[defectList->at(index.row()).id-1]; - } - return QVariant(); + default: + return QVariant(); + } + } + else + { + if (Qt::SizeHintRole == role){ + return QVariant(10); + } + } + return QVariant(); } QVariant NotifyTableModel::headerData(int section, Qt::Orientation orientation, int role) const { - if (role != Qt::DisplayRole) - return QVariant(); + if (role != Qt::DisplayRole) + return QVariant(); - if (orientation == Qt::Horizontal) - return headerStrings.at(section); - else - if(orientation == Qt::Vertical) - return QString("%1").arg(section); + if (orientation == Qt::Horizontal) + return _headerStrings.at(section); + else + if (orientation == Qt::Vertical) + return QString("%1").arg(section); - return QVariant(); + return QVariant(); } -bool NotifyTableModel::insertRows(int position, int rows, const QModelIndex &index) +bool NotifyTableModel::insertRows(int position, int rows, const QModelIndex& index) { - Q_UNUSED(index); - beginInsertRows(QModelIndex(), position, position+rows-1); + Q_UNUSED(index); -// for (int row=0; row < rows; ++row) { -// _list->append(position); -// } + if (-1 == position || -1 == rows) + return false; + beginInsertRows(QModelIndex(), position, position + rows - 1); - endInsertRows(); - return true; + for (int i = 0; i < rows; ++i) { + _list.insert(position + i, new NotificationItem()); + } + + endInsertRows(); + return true; } - bool NotifyTableModel::removeRows(int position, int rows, const QModelIndex &index) - { - Q_UNUSED(index); - beginRemoveRows(QModelIndex(), position, position+rows-1); +bool NotifyTableModel::removeRows(int position, int rows, const QModelIndex& index) +{ + Q_UNUSED(index); - for (int row=0; row < rows; ++row) { - _list->removeAt(position); - } + if ((-1 == position) || (-1 == rows) ) + return false; - endRemoveRows(); - return true; - } + beginRemoveRows(QModelIndex(), position, position + rows - 1); + + for (int row = 0; row < rows; ++row) { + _list.removeAt(position); + } + + endRemoveRows(); + return true; +} void NotifyTableModel::entryUpdated(int offset) { - QModelIndex idx = index(offset, 0); - emit dataChanged(idx, idx); + QModelIndex idx = index(offset, 0); + emit dataChanged(idx, idx); } -void NotifyTableModel::entryAdded(int position) +void NotifyTableModel::entryAdded(NotificationItem* item) { - insertRows(position, 1,QModelIndex()); + insertRows(rowCount(), 1, QModelIndex()); + NotificationItem* tmp = _list.at(rowCount() - 1); + _list.replace(rowCount() - 1, item); + delete tmp; + entryUpdated(rowCount() - 1); +} + +Qt::DropActions NotifyTableModel::supportedDropActions() const +{ + return Qt::MoveAction; +} + +QStringList NotifyTableModel::mimeTypes() const +{ + QStringList types; + types << mime_type_notify_table; + return types; +} + +bool NotifyTableModel::dropMimeData( const QMimeData * data, Qt::DropAction action, int row, + int column, const QModelIndex& parent) +{ + if (action == Qt::IgnoreAction) + return true; + + if (!data->hasFormat(mime_type_notify_table)) + return false; + + int beginRow = -1; + + if (row != -1) + beginRow = row; + else { + if (parent.isValid()) + beginRow = parent.row(); + else + beginRow = rowCount(QModelIndex()); + } + + if (-1 == beginRow) + return false; + + QByteArray encodedData = data->data(mime_type_notify_table); + QDataStream stream(&encodedData, QIODevice::ReadOnly); + int rows = beginRow; + // read next item from input MIME and drop into the table line by line + while(!stream.atEnd()) { + qint32 ptr; + stream >> ptr; + NotificationItem* item = reinterpret_cast(ptr); + int dragged = _list.indexOf(item); + // we can drag item from top rows to bottom (DOWN_DIRECTION), + // or from bottom rows to top rows (UP_DIRECTION) + enum { UP_DIRECTION, DOWN_DIRECTION }; + int direction = (dragged < rows) ? DOWN_DIRECTION : (dragged += 1, UP_DIRECTION); + // check drop bounds + if (dragged < 0 || ((dragged + 1) >= _list.size() && direction == DOWN_DIRECTION) || dragged == rows) { + qNotifyDebug() << "no such item"; + continue; + } + // addiional check in case dropping of multiple rows + if(rows + direction > _list.size()) continue; + + Q_ASSERT(insertRows(rows + direction, 1, QModelIndex())); + _list.replace(rows + direction, item); + Q_ASSERT(removeRows(dragged, 1, QModelIndex())); + if (direction == UP_DIRECTION) + ++rows; + }; + + QModelIndex idxTopLeft = index(beginRow, 0, QModelIndex()); + QModelIndex idxBotRight = index(beginRow, columnCount(QModelIndex()), QModelIndex()); + emit dataChanged(idxTopLeft, idxBotRight); + return true; +} + +QMimeData* NotifyTableModel::mimeData(const QModelIndexList& indexes) const +{ + QMimeData* mimeData = new QMimeData(); + QByteArray encodedData; + + QDataStream stream(&encodedData, QIODevice::WriteOnly); + int rows = 0; + foreach (const QModelIndex& index, indexes) { + if (!index.column()) { + qint32 item = reinterpret_cast(_list.at(index.row())); + stream << item; + ++rows; + } + } + mimeData->setData(mime_type_notify_table, encodedData); + return mimeData; +} + +void NotifyTableModel::dropRows(int position, int count) const +{ + for (int row = 0; row < count; ++row) { + _list.removeAt(position); + } } diff --git a/ground/openpilotgcs/src/plugins/notify/notifytablemodel.h b/ground/openpilotgcs/src/plugins/notify/notifytablemodel.h index 65aa82a86..dd2e765bd 100644 --- a/ground/openpilotgcs/src/plugins/notify/notifytablemodel.h +++ b/ground/openpilotgcs/src/plugins/notify/notifytablemodel.h @@ -31,49 +31,60 @@ #include #include -#include "notifypluginconfiguration.h" +#include "notificationitem.h" + +enum ColumnNames { eMessageName, eRepeatValue, eExpireTimer, eTurnOn }; class NotifyTableModel : public QAbstractTableModel { - Q_OBJECT - public: - NotifyTableModel(QList *parentList, const QStringList& parentHeaderList, QObject *parent = 0) - : QAbstractTableModel(parent), - _list(parentList), - headerStrings(parentHeaderList) - { } + Q_OBJECT - int rowCount(const QModelIndex &parent = QModelIndex()) const - { - return _list->count(); - } + enum {eColumnCount = 4 }; - int columnCount(const QModelIndex &/*parent*/) const - { - return 3; - } +public: - Qt::ItemFlags flags(const QModelIndex &index) const - { - if (!index.isValid()) - return Qt::ItemIsEnabled; + NotifyTableModel(QList& parentList, QObject* parent = 0); + int rowCount(const QModelIndex& parent = QModelIndex()) const + { + return _list.count(); + } - return QAbstractItemModel::flags(index) | Qt::ItemIsEditable; - } + int columnCount(const QModelIndex &/*parent*/) const + { + return eColumnCount; + } - bool setData(const QModelIndex &index, const QVariant &value, int role); - QVariant data(const QModelIndex &index, int role) const; - QVariant headerData(int section, Qt::Orientation orientation, int role) const; - bool insertRows(int position, int rows, const QModelIndex &index); - bool removeRows(int position, int rows, const QModelIndex &index); + Qt::ItemFlags flags(const QModelIndex &index) const + { + if (!index.isValid()) + return Qt::ItemIsEnabled | Qt::ItemIsDropEnabled; + + return QAbstractItemModel::flags(index) | Qt::ItemIsEditable | Qt::ItemIsDragEnabled | Qt::ItemIsDropEnabled; + } + QStringList mimeTypes() const; + Qt::DropActions supportedDropActions() const; + bool dropMimeData( const QMimeData * data, Qt::DropAction action, int row, + int column, const QModelIndex& parent); + QMimeData* mimeData(const QModelIndexList &indexes) const; + + + bool setData(const QModelIndex &index, const QVariant &value, int role); + QVariant data(const QModelIndex &index, int role) const; + QVariant headerData(int section, Qt::Orientation orientation, int role) const; + bool insertRows(int position, int rows, const QModelIndex &index); + bool removeRows(int position, int rows, const QModelIndex &index); + void entryAdded(NotificationItem* item); + +signals: + void dragRows(int position, int count); private slots: - void entryUpdated(int offset); - void entryAdded(int position); + void entryUpdated(int offset); + void dropRows(int position, int count) const; + private: - QList *_list; - QStringList headerStrings; + QList& _list; + QStringList _headerStrings; }; - #endif // NOTIFYTABLEMODEL_H diff --git a/ground/openpilotgcs/src/plugins/serialconnection/serialplugin.cpp b/ground/openpilotgcs/src/plugins/serialconnection/serialplugin.cpp index 23bb8f9f9..d799e843f 100644 --- a/ground/openpilotgcs/src/plugins/serialconnection/serialplugin.cpp +++ b/ground/openpilotgcs/src/plugins/serialconnection/serialplugin.cpp @@ -209,9 +209,9 @@ BaudRateType SerialConnection::stringToBaud(QString str) if(str=="1200") return BAUD1200; else if(str=="2400") - return BAUD1200; - else if(str== "4800") return BAUD2400; + else if(str== "4800") + return BAUD4800; else if(str== "9600") return BAUD9600; else if(str== "19200") @@ -219,7 +219,7 @@ BaudRateType SerialConnection::stringToBaud(QString str) else if(str== "38400") return BAUD38400; else if(str== "57600") - return BAUD56000; + return BAUD57600; else if(str== "115200") return BAUD115200; else if(str== "230400") @@ -229,7 +229,7 @@ BaudRateType SerialConnection::stringToBaud(QString str) else if(str== "921600") return BAUD921600; else - return BAUD56000; + return BAUD57600; } SerialPlugin::SerialPlugin() diff --git a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.cpp b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.cpp index 64ad9544c..ac2e4bcee 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjecttreemodel.cpp @@ -95,7 +95,7 @@ void UAVObjectTreeModel::addDataObject(UAVDataObject *obj) int index = root->objIds().indexOf(obj->getObjID()); addInstance(obj, root->child(index)); } else { - DataObjectTreeItem *data = new DataObjectTreeItem(obj->getName()); + DataObjectTreeItem *data = new DataObjectTreeItem(obj->getName() + " (" + QString::number(obj->getNumBytes()) + " bytes)"); connect(data, SIGNAL(updateHighlight(TreeItem*)), this, SLOT(updateHighlight(TreeItem*))); int index = root->nameIndex(obj->getName()); root->insert(index, data); diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro index d65ac5753..70937189b 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro @@ -73,7 +73,8 @@ HEADERS += $$UAVOBJECT_SYNTHETICS/accessorydesired.h \ $$UAVOBJECT_SYNTHETICS/gcsreceiver.h \ $$UAVOBJECT_SYNTHETICS/receiveractivity.h \ $$UAVOBJECT_SYNTHETICS/attitudesettings.h \ - $$UAVOBJECT_SYNTHETICS/cameradesired.h + $$UAVOBJECT_SYNTHETICS/cameradesired.h \ + $$UAVOBJECT_SYNTHETICS/faultsettings.h SOURCES += $$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \ $$UAVOBJECT_SYNTHETICS/baroaltitude.cpp \ @@ -126,4 +127,5 @@ SOURCES += $$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \ $$UAVOBJECT_SYNTHETICS/gcsreceiver.cpp \ $$UAVOBJECT_SYNTHETICS/receiveractivity.cpp \ $$UAVOBJECT_SYNTHETICS/attitudesettings.cpp \ - $$UAVOBJECT_SYNTHETICS/cameradesired.cpp + $$UAVOBJECT_SYNTHETICS/cameradesired.cpp \ + $$UAVOBJECT_SYNTHETICS/faultsettings.cpp diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjecttemplate.m b/ground/openpilotgcs/src/plugins/uavobjects/uavobjecttemplate.m index 5cfcb6068..96d727dff 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjecttemplate.m +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjecttemplate.m @@ -1,39 +1,54 @@ -function [] = OPLogConvert(logfile) +function [] = OPLogConvert(varargin) %% Define indices and arrays of structures to hold data % THIS FILE IS AUTOMATICALLY GENERATED. -$(ALLOCATIONCODE) + +outputType='mat'; %Default output is a .mat file if nargin==0 %% if (exist('uigetfile')) - [FileName, PathName]=uigetfile; + [FileName, PathName]=uigetfile('*.opl'); logfile=fullfile(PathName, FileName); else error('Your technical computing program does not support file choosers. Please input the file name in the argument. ') + end +elseif nargin>0 + logfile=varargin{1}; + if nargin>1 + outputType=varargin{2}; end end +if ~strcmpi(outputType,'mat') && ~strcmpi(outputType,'csv') + error('Incorrect file format specified. Second argument must be ''mat'' or ''csv''.'); +end + +$(ALLOCATIONCODE) + + fid = fopen(logfile); +correctMsgByte=hex2dec('20'); +correctSyncByte=hex2dec('3C'); % Parse log file, entry by entry while (1) %% Read logging header - timestamp = fread(fid, 1, 'uint32'); + timestamp = fread(fid, 1, '*uint32'); if (feof(fid)); break; end - datasize = fread(fid, 1, 'int64'); + datasize = fread(fid, 1, '*int64'); %% Read message header % get sync field (0x3C, 1 byte) sync = fread(fid, 1, 'uint8'); - if sync ~= hex2dec('3C') + if sync ~= correctSyncByte disp ('Wrong sync byte'); return end % get msg type (quint8 1 byte ) should be 0x20, ignore the rest? msgType = fread(fid, 1, 'uint8'); - if msgType ~= hex2dec('20') + if msgType ~= correctMsgByte disp ('Wrong msgType'); return end @@ -42,12 +57,15 @@ while (1) % get obj id (quint32 4 bytes) objID = fread(fid, 1, 'uint32'); + if (isempty(objID)) %End of file + break; + end %% Read object switch objID $(SWITCHCODE) otherwise - disp(['Unknown object ID: 0x' dec2hex(objID)]); + disp(['Unknown object ID: 0x' dec2hex(objID)]); msgBytesLeft = datasize - 1 - 1 - 2 - 4; fread(fid, msgBytesLeft, 'uint8'); end @@ -60,13 +78,52 @@ fclose(fid); % Trim output structs $(CLEANUPCODE) -matfile = strrep(logfile,'opl','mat'); -save(matfile $(SAVEOBJECTSCODE)); - +if strcmpi(outputType,'mat') + matfile = strrep(logfile,'opl','mat'); + save(matfile $(SAVEOBJECTSCODE)); +else +$(EXPORTCSVCODE); +end %% Object reading functions $(FUNCTIONSCODE) +% This function prunes the excess pre-allocated space +function [structOut]=PruneStructOfArrays(structIn, lastIndex) + + fieldNames = fieldnames(structIn); + for i=1:length(fieldNames) + structOut.(fieldNames{i})=structIn.(fieldNames{i})(1:lastIndex); + end + + +function OPLog2csv(structIn, structName, logfile) + %Get each field name from the structure + fieldNames = fieldnames(structIn); + + %Create a text string with the field names + headerOut=sprintf('%s,',fieldNames{:}); + headerOut=headerOut(1:end-1); %Trim off last `,` and `\t` + + %Assign the structure arrays to a matrix. + matOut=zeros(max(size(structIn.(fieldNames{1}))), length(fieldNames)); + + if isempty(structIn.(fieldNames{1})); + matOut=[]; + else + for i=1:length(fieldNames) + matOut(:,i)=structIn.(fieldNames{i}); + end + end + % Create filename by replacing opl by csv + [path, name] = fileparts(logfile); + csvDirName=[name '_csv']; + [dummyA, dummyB]=mkdir(fullfile(path, csvDirName)); %Dummy outputs so the program doens't throw warnings about "Directory already exists" + csvfile=fullfile(path, csvDirName , [name '.csv']); + + %Write to csv. + dlmwrite(csvfile, headerOut, ''); + dlmwrite(csvfile, matOut, '-append'); diff --git a/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.cpp b/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.cpp index 7295f79c3..4c218379d 100644 --- a/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.cpp +++ b/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.cpp @@ -28,6 +28,14 @@ #include #include +//#define UAVTALK_DEBUG +#ifdef UAVTALK_DEBUG + #include "qxtlogger.h" + #define UAVTALK_QXTLOG_DEBUG(args...) qxtLog->debug(args...) +#else // UAVTALK_DEBUG + #define UAVTALK_QXTLOG_DEBUG(args...) +#endif // UAVTALK_DEBUG + #define SYNC_VAL 0x3C const quint8 UAVTalk::crc_table[256] = { @@ -207,7 +215,10 @@ bool UAVTalk::processInputByte(quint8 rxbyte) case STATE_SYNC: if (rxbyte != SYNC_VAL) + { + UAVTALK_QXTLOG_DEBUG("UAVTalk: Sync->Sync (" + QString::number(rxbyte) + " " + QString("0x%1").arg(rxbyte,2,16) + ")"); break; + } // Initialize and update CRC rxCS = updateCRC(0, rxbyte); @@ -215,6 +226,7 @@ bool UAVTalk::processInputByte(quint8 rxbyte) rxPacketLength = 1; rxState = STATE_TYPE; + UAVTALK_QXTLOG_DEBUG("UAVTalk: Sync->Type"); break; case STATE_TYPE: @@ -225,6 +237,7 @@ bool UAVTalk::processInputByte(quint8 rxbyte) if ((rxbyte & TYPE_MASK) != TYPE_VER) { rxState = STATE_SYNC; + UAVTALK_QXTLOG_DEBUG("UAVTalk: Type->Sync"); break; } @@ -233,6 +246,7 @@ bool UAVTalk::processInputByte(quint8 rxbyte) packetSize = 0; rxState = STATE_SIZE; + UAVTALK_QXTLOG_DEBUG("UAVTalk: Type->Size"); rxCount = 0; break; @@ -245,6 +259,7 @@ bool UAVTalk::processInputByte(quint8 rxbyte) { packetSize += rxbyte; rxCount++; + UAVTALK_QXTLOG_DEBUG("UAVTalk: Size->Size"); break; } @@ -253,11 +268,13 @@ bool UAVTalk::processInputByte(quint8 rxbyte) if (packetSize < MIN_HEADER_LENGTH || packetSize > MAX_HEADER_LENGTH + MAX_PAYLOAD_LENGTH) { // incorrect packet size rxState = STATE_SYNC; + UAVTALK_QXTLOG_DEBUG("UAVTalk: Size->Sync"); break; } rxCount = 0; rxState = STATE_OBJID; + UAVTALK_QXTLOG_DEBUG("UAVTalk: Size->ObjID"); break; case STATE_OBJID: @@ -267,7 +284,10 @@ bool UAVTalk::processInputByte(quint8 rxbyte) rxTmpBuffer[rxCount++] = rxbyte; if (rxCount < 4) + { + UAVTALK_QXTLOG_DEBUG("UAVTalk: ObjID->ObjID"); break; + } // Search for object, if not found reset state machine rxObjId = (qint32)qFromLittleEndian(rxTmpBuffer); @@ -277,6 +297,7 @@ bool UAVTalk::processInputByte(quint8 rxbyte) { stats.rxErrors++; rxState = STATE_SYNC; + UAVTALK_QXTLOG_DEBUG("UAVTalk: ObjID->Sync (badtype)"); break; } @@ -297,6 +318,7 @@ bool UAVTalk::processInputByte(quint8 rxbyte) { stats.rxErrors++; rxState = STATE_SYNC; + UAVTALK_QXTLOG_DEBUG("UAVTalk: ObjID->Sync (oversize)"); break; } @@ -305,6 +327,7 @@ bool UAVTalk::processInputByte(quint8 rxbyte) { // packet error - mismatched packet size stats.rxErrors++; rxState = STATE_SYNC; + UAVTALK_QXTLOG_DEBUG("UAVTalk: ObjID->Sync (length mismatch)"); break; } @@ -314,6 +337,7 @@ bool UAVTalk::processInputByte(quint8 rxbyte) // This is a non-existing object, just skip to checksum // and we'll send a NACK next. rxState = STATE_CS; + UAVTALK_QXTLOG_DEBUG("UAVTalk: ObjID->CSum (no obj)"); rxInstId = 0; rxCount = 0; } @@ -321,15 +345,22 @@ bool UAVTalk::processInputByte(quint8 rxbyte) { // If there is a payload get it, otherwise receive checksum if (rxLength > 0) + { rxState = STATE_DATA; + UAVTALK_QXTLOG_DEBUG("UAVTalk: ObjID->Data (needs data)"); + } else + { rxState = STATE_CS; + UAVTALK_QXTLOG_DEBUG("UAVTalk: ObjID->Checksum"); + } rxInstId = 0; rxCount = 0; } else { rxState = STATE_INSTID; + UAVTALK_QXTLOG_DEBUG("UAVTalk: ObjID->InstID"); rxCount = 0; } } @@ -343,7 +374,10 @@ bool UAVTalk::processInputByte(quint8 rxbyte) rxTmpBuffer[rxCount++] = rxbyte; if (rxCount < 2) + { + UAVTALK_QXTLOG_DEBUG("UAVTalk: InstID->InstID"); break; + } rxInstId = (qint16)qFromLittleEndian(rxTmpBuffer); @@ -351,10 +385,15 @@ bool UAVTalk::processInputByte(quint8 rxbyte) // If there is a payload get it, otherwise receive checksum if (rxLength > 0) + { rxState = STATE_DATA; + UAVTALK_QXTLOG_DEBUG("UAVTalk: InstID->Data"); + } else + { rxState = STATE_CS; - + UAVTALK_QXTLOG_DEBUG("UAVTalk: InstID->CSum"); + } break; case STATE_DATA: @@ -364,9 +403,13 @@ bool UAVTalk::processInputByte(quint8 rxbyte) rxBuffer[rxCount++] = rxbyte; if (rxCount < rxLength) + { + UAVTALK_QXTLOG_DEBUG("UAVTalk: Data->Data"); break; + } rxState = STATE_CS; + UAVTALK_QXTLOG_DEBUG("UAVTalk: Data->CSum"); rxCount = 0; break; @@ -379,6 +422,7 @@ bool UAVTalk::processInputByte(quint8 rxbyte) { // packet error - faulty CRC stats.rxErrors++; rxState = STATE_SYNC; + UAVTALK_QXTLOG_DEBUG("UAVTalk: CSum->Sync (badcrc)"); break; } @@ -386,6 +430,7 @@ bool UAVTalk::processInputByte(quint8 rxbyte) { // packet error - mismatched packet size stats.rxErrors++; rxState = STATE_SYNC; + UAVTALK_QXTLOG_DEBUG("UAVTalk: CSum->Sync (length mismatch)"); break; } @@ -396,11 +441,13 @@ bool UAVTalk::processInputByte(quint8 rxbyte) mutex->unlock(); rxState = STATE_SYNC; + UAVTALK_QXTLOG_DEBUG("UAVTalk: CSum->Sync (OK)"); break; default: rxState = STATE_SYNC; stats.rxErrors++; + UAVTALK_QXTLOG_DEBUG("UAVTalk: ???->Sync"); } // Done diff --git a/ground/openpilotgcs/src/plugins/uploader/devicewidget.cpp b/ground/openpilotgcs/src/plugins/uploader/devicewidget.cpp index 9e57a4225..cf4315596 100644 --- a/ground/openpilotgcs/src/plugins/uploader/devicewidget.cpp +++ b/ground/openpilotgcs/src/plugins/uploader/devicewidget.cpp @@ -358,8 +358,10 @@ void deviceWidget::loadFirmware() */ void deviceWidget::uploadFirmware() { + myDevice->updateButton->setEnabled(false); if (!m_dfu->devices[deviceID].Writable) { status("Device not writable!", STATUSICON_FAIL); + myDevice->updateButton->setEnabled(true); return; } @@ -378,6 +380,7 @@ void deviceWidget::uploadFirmware() int firmwareBoard = ((desc.at(12)&0xff)<<8) + (desc.at(13)&0xff); if (firmwareBoard != board) { status("Error: firmware does not match board", STATUSICON_FAIL); + myDevice->updateButton->setEnabled(true); return; } // Check the firmware embedded in the file: @@ -385,6 +388,7 @@ void deviceWidget::uploadFirmware() QByteArray fileHash = QCryptographicHash::hash(loadedFW.left(loadedFW.length()-100), QCryptographicHash::Sha1); if (firmwareHash != fileHash) { status("Error: firmware file corrupt", STATUSICON_FAIL); + myDevice->updateButton->setEnabled(true); return; } } else { @@ -400,6 +404,7 @@ void deviceWidget::uploadFirmware() if(!m_dfu->enterDFU(deviceID)) { status("Error:Could not enter DFU mode", STATUSICON_FAIL); + myDevice->updateButton->setEnabled(true); return; } OP_DFU::Status ret=m_dfu->StatusRequest(); @@ -412,6 +417,7 @@ void deviceWidget::uploadFirmware() bool retstatus = m_dfu->UploadFirmware(filename,verify, deviceID); if(!retstatus ) { status("Could not start upload", STATUSICON_FAIL); + myDevice->updateButton->setEnabled(true); return; } status("Uploading, please wait...", STATUSICON_RUNNING); @@ -465,6 +471,7 @@ void deviceWidget::downloadFinished() */ void deviceWidget::uploadFinished(OP_DFU::Status retstatus) { + myDevice->updateButton->setEnabled(true); disconnect(m_dfu, SIGNAL(uploadFinished(OP_DFU::Status)), this, SLOT(uploadFinished(OP_DFU::Status))); disconnect(m_dfu, SIGNAL(progressUpdated(int)), this, SLOT(setProgress(int))); disconnect(m_dfu, SIGNAL(operationProgress(QString)), this, SLOT(dfuStatus(QString))); diff --git a/ground/openpilotgcs/src/plugins/uploader/op_dfu.cpp b/ground/openpilotgcs/src/plugins/uploader/op_dfu.cpp index 961103d22..0143a180b 100644 --- a/ground/openpilotgcs/src/plugins/uploader/op_dfu.cpp +++ b/ground/openpilotgcs/src/plugins/uploader/op_dfu.cpp @@ -509,7 +509,7 @@ int DFUObject::AbortOperation(void) /** Starts the firmware (leaves bootloader and boots the main software) */ -int DFUObject::JumpToApp() +int DFUObject::JumpToApp(bool safeboot) { char buf[BUF_LEN]; buf[0] =0x02;//reportID @@ -520,8 +520,17 @@ int DFUObject::JumpToApp() buf[5] = 0; buf[6] = 0; buf[7] = 0; - buf[8] = 0; - buf[9] = 0; + if (safeboot) + { + /* force system to safe boot mode (hwsettings == defaults) */ + buf[8] = 0x5A; + buf[9] = 0xFE; + } + else + { + buf[8] = 0; + buf[9] = 0; + } return sendData(buf, BUF_LEN); //return hidHandle.send(0,buf, BUF_LEN, 500); diff --git a/ground/openpilotgcs/src/plugins/uploader/op_dfu.h b/ground/openpilotgcs/src/plugins/uploader/op_dfu.h index 79624b546..812f3f2fb 100644 --- a/ground/openpilotgcs/src/plugins/uploader/op_dfu.h +++ b/ground/openpilotgcs/src/plugins/uploader/op_dfu.h @@ -129,7 +129,7 @@ namespace OP_DFU { // Service commands: bool enterDFU(int const &devNumber); bool findDevices(); - int JumpToApp(); + int JumpToApp(bool); int ResetDevice(void); OP_DFU::Status StatusRequest(); bool EndOperation(); diff --git a/ground/openpilotgcs/src/plugins/uploader/uploader.ui b/ground/openpilotgcs/src/plugins/uploader/uploader.ui index d66fc02ef..540d69302 100644 --- a/ground/openpilotgcs/src/plugins/uploader/uploader.ui +++ b/ground/openpilotgcs/src/plugins/uploader/uploader.ui @@ -6,7 +6,7 @@ 0 0 - 580 + 583 350 @@ -50,6 +50,24 @@ menu on the right. + + + + true + + + Boots the system into safe mode (ie. default HwSettings). +Only useful if the system is halted +(mainboard blue LED blinking slowly, orange LED off) + +If telemetry is not running, select the link using the dropdown +menu on the right. + + + Safe Boot + + + @@ -126,6 +144,26 @@ halting a running board. + + + + + + + + :/core/images/helpicon.svg:/core/images/helpicon.svg + + + + 30 + 30 + + + + true + + + @@ -148,14 +186,14 @@ halting a running board. <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> <html><head><meta name="qrichtext" content="1" /><style type="text/css"> p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">To upgrade the firmware in your boards, proceed as follows:</p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">- Connect telemetry</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">- Once telemetry is running, press &quot;Halt&quot; above</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">- You will get a list of devices.</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">- You can then upload/download to/from each board as you wish</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">- You can resume operations by pressing &quot;Boot&quot;</p></body></html> +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">To upgrade the firmware in your boards, proceed as follows:</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">- Connect telemetry</span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">- Once telemetry is running, press &quot;Halt&quot; above</span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">- You will get a list of devices.</span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">- You can then upload/download to/from each board as you wish</span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">- You can resume operations by pressing &quot;Boot&quot;</span></p></body></html> @@ -170,14 +208,16 @@ p, li { white-space: pre-wrap; } <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> <html><head><meta name="qrichtext" content="1" /><style type="text/css"> p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;"> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"></p></body></html> +</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"></p></body></html> - + + + diff --git a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp index c0a1aea90..851334c86 100755 --- a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp @@ -52,6 +52,7 @@ UploaderGadgetWidget::UploaderGadgetWidget(QWidget *parent) : QWidget(parent) connect(m_config->haltButton, SIGNAL(clicked()), this, SLOT(goToBootloader())); connect(m_config->resetButton, SIGNAL(clicked()), this, SLOT(systemReset())); connect(m_config->bootButton, SIGNAL(clicked()), this, SLOT(systemBoot())); + connect(m_config->safeBootButton, SIGNAL(clicked()), this, SLOT(systemSafeBoot())); connect(m_config->rescueButton, SIGNAL(clicked()), this, SLOT(systemRescue())); Core::ConnectionManager *cm = Core::ICore::instance()->connectionManager(); connect(cm,SIGNAL(deviceConnected(QIODevice*)),this,SLOT(onPhisicalHWConnect())); @@ -63,6 +64,7 @@ UploaderGadgetWidget::UploaderGadgetWidget(QWidget *parent) : QWidget(parent) connect(m_config->refreshPorts, SIGNAL(clicked()), this, SLOT(getSerialPorts())); + connect(m_config->pbHelp,SIGNAL(clicked()),this,SLOT(openHelp())); // And check whether by any chance we are not already connected if (telMngr->isConnected()) { @@ -117,6 +119,7 @@ QString UploaderGadgetWidget::getPortDevice(const QString &friendName) void UploaderGadgetWidget::onPhisicalHWConnect() { m_config->bootButton->setEnabled(false); + m_config->safeBootButton->setEnabled(false); m_config->rescueButton->setEnabled(false); m_config->telemetryLink->setEnabled(false); } @@ -132,6 +135,7 @@ void UploaderGadgetWidget::populate() { m_config->haltButton->setEnabled(true); m_config->resetButton->setEnabled(true); + m_config->safeBootButton->setEnabled(false); m_config->bootButton->setEnabled(false); m_config->rescueButton->setEnabled(false); m_config->telemetryLink->setEnabled(false); @@ -155,6 +159,7 @@ void UploaderGadgetWidget::onAutopilotDisconnect(){ m_config->haltButton->setEnabled(false); m_config->resetButton->setEnabled(false); m_config->bootButton->setEnabled(true); + m_config->safeBootButton->setEnabled(true); if (currentStep == IAP_STATE_BOOTLOADER) { m_config->rescueButton->setEnabled(false); m_config->telemetryLink->setEnabled(false); @@ -311,6 +316,7 @@ void UploaderGadgetWidget::goToBootloader(UAVObject* callerObj, bool success) */ // Need to re-enable in case we were not connected m_config->bootButton->setEnabled(true); + m_config->safeBootButton->setEnabled(true); /* m_config->telemetryLink->setEnabled(false); m_config->rescueButton->setEnabled(false); @@ -348,14 +354,25 @@ void UploaderGadgetWidget::systemReset() goToBootloader(); } +void UploaderGadgetWidget::systemBoot() +{ + commonSystemBoot(false); +} + +void UploaderGadgetWidget::systemSafeBoot() +{ + commonSystemBoot(true); +} + /** Tells the system to boot (from Bootloader state) */ -void UploaderGadgetWidget::systemBoot() +void UploaderGadgetWidget::commonSystemBoot(bool safeboot) { clearLog(); m_config->bootButton->setEnabled(false); + m_config->safeBootButton->setEnabled(false); // Suspend telemety & polling in case it is not done yet Core::ConnectionManager *cm = Core::ICore::instance()->connectionManager(); @@ -379,11 +396,12 @@ void UploaderGadgetWidget::systemBoot() delete dfu; dfu = NULL; m_config->bootButton->setEnabled(true); + m_config->safeBootButton->setEnabled(true); m_config->rescueButton->setEnabled(true); // Boot not possible, maybe Rescue OK? return; } log("Booting system..."); - dfu->JumpToApp(); + dfu->JumpToApp(safeboot); // Restart the polling thread cm->resumePolling(); m_config->rescueButton->setEnabled(true); @@ -530,6 +548,7 @@ void UploaderGadgetWidget::systemRescue() m_config->haltButton->setEnabled(false); m_config->resetButton->setEnabled(false); m_config->bootButton->setEnabled(true); + m_config->safeBootButton->setEnabled(true); m_config->rescueButton->setEnabled(false); currentStep = IAP_STATE_BOOTLOADER; // So that we can boot from the GUI afterwards. } @@ -627,10 +646,13 @@ void UploaderGadgetWidget::versionMatchCheck() qDebug()<0) - msg->showMessage(QString("Incompatible GCS and FW detected, you should upgrade your board's Firmware to %1 version.").arg(gcsDescription)); - else - msg->showMessage(QString("Incompatible GCS and FW detected, you should upgrade your GCS to %1 version.").arg(boardDescription.gitTag+":"+boardDescription.buildDate)); - + msg->showMessage(QString(tr("GCS and FW versions do not match which can cause configuration problems.")) + " \n" + + QString(tr("GCS Versions: ")) + gcsDescription + " \n" + + QString(tr("FW Versions: ")) + boardDescription.gitTag+":"+boardDescription.buildDate); } } +void UploaderGadgetWidget::openHelp() +{ + + QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/Uploader+Plugin", QUrl::StrictMode) ); +} diff --git a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.h b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.h index 9b1fa1433..2c6814827 100755 --- a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.h @@ -55,6 +55,7 @@ #include "devicedescriptorstruct.h" #include #include +#include using namespace OP_DFU; @@ -74,6 +75,7 @@ public slots: void onAutopilotConnect(); void onAutopilotDisconnect(); void populate(); + void openHelp(); private: Ui_UploaderWidget *m_config; DFUObject *dfu; @@ -94,6 +96,8 @@ private slots: void goToBootloader(UAVObject* = NULL, bool = false); void systemReset(); void systemBoot(); + void systemSafeBoot(); + void commonSystemBoot(bool = false); void systemRescue(); void getSerialPorts(); void perform(); diff --git a/ground/uavobjgenerator/generators/matlab/uavobjectgeneratormatlab.cpp b/ground/uavobjgenerator/generators/matlab/uavobjectgeneratormatlab.cpp index c7cedddda..9f160ad52 100644 --- a/ground/uavobjgenerator/generators/matlab/uavobjectgeneratormatlab.cpp +++ b/ground/uavobjgenerator/generators/matlab/uavobjectgeneratormatlab.cpp @@ -54,6 +54,7 @@ bool UAVObjectGeneratorMatlab::generate(UAVObjectParser* parser,QString template matlabCodeTemplate.replace( QString("$(CLEANUPCODE)"), matlabCleanupCode); matlabCodeTemplate.replace( QString("$(SAVEOBJECTSCODE)"), matlabSaveObjectsCode); matlabCodeTemplate.replace( QString("$(FUNCTIONSCODE)"), matlabFunctionsCode); + matlabCodeTemplate.replace( QString("$(EXPORTCSVCODE)"), matlabExportCsvCode); bool res = writeFile( matlabOutputPath.absolutePath() + "/OPLogConvert.m", matlabCodeTemplate ); if (!res) { @@ -78,7 +79,7 @@ bool UAVObjectGeneratorMatlab::process_object(ObjectInfo* info) QString objectTableName(objectName); QString tableIdxName(objectName.toLower() + "Idx"); QString functionName("Read" + info->name + "Object"); - QString functionCall(functionName + "(fid, timestamp)"); + QString functionCall(functionName + "(fid, timestamp, "); QString objectID(QString().setNum(info->id)); QString isSingleInst = boolTo01String( info->isSingleInst ); @@ -87,7 +88,7 @@ bool UAVObjectGeneratorMatlab::process_object(ObjectInfo* info) // Generate allocation code (will replace the $(ALLOCATIONCODE) tag) // //===================================================================// // matlabSwitchCode.append("\t\tcase " + objectID + "\n"); - matlabAllocationCode.append("\n\t" + tableIdxName + " = 1;\n"); + matlabAllocationCode.append("\n\t" + tableIdxName + " = 0;\n"); QString type; QString allocfields; if (0){ @@ -97,7 +98,7 @@ bool UAVObjectGeneratorMatlab::process_object(ObjectInfo* info) type = fieldTypeStrMatlab[info->fields[n]->type]; // Append field if ( info->fields[n]->numElements > 1 ) - allocfields.append("\t" + objectTableName + "(1)." + info->fields[n]->name + " = zeros(1," + QString::number(info->fields[n]->numElements, 10) + ");\n"); + allocfields.append("\t" + objectTableName + "(1)." + info->fields[n]->name + " = zeros(" + QString::number(info->fields[n]->numElements, 10) + ",1);\n"); else allocfields.append("\t" + objectTableName + "(1)." + info->fields[n]->name + " = 0;\n"); } @@ -112,52 +113,64 @@ bool UAVObjectGeneratorMatlab::process_object(ObjectInfo* info) type = fieldTypeStrMatlab[info->fields[n]->type]; // Append field if ( info->fields[n]->numElements > 1 ) - allocfields.append(",...\n\t\t '" + info->fields[n]->name + "', zeros(1," + QString::number(info->fields[n]->numElements, 10) + ")"); + allocfields.append(",...\n\t\t '" + info->fields[n]->name + "', zeros(" + QString::number(info->fields[n]->numElements, 10) + ",1)"); else allocfields.append(",...\n\t\t '" + info->fields[n]->name + "', 0"); } allocfields.append(");\n"); - } + } matlabAllocationCode.append(allocfields); - matlabAllocationCode.append("\t" + objectTableName.toUpper() + "_OBJID=" + objectID + ";\n"); + matlabAllocationCode.append("\t" + objectTableName.toUpper() + "_OBJID=" + objectID + ";\n"); - //=============================================================// + //==============================================================// // Generate 'Switch:' code (will replace the $(SWITCHCODE) tag) // - //=============================================================// + //==============================================================// + + + matlabSwitchCode.append("\t\tcase " + objectTableName.toUpper() + "_OBJID\n"); - matlabSwitchCode.append("\t\t\t" + objectTableName + "(" + tableIdxName +") = " + functionCall + ";\n"); - matlabSwitchCode.append("\t\t\t" + tableIdxName + " = " + tableIdxName +" + 1;\n"); - matlabSwitchCode.append("\t\t\tif " + tableIdxName + " > length(" + objectTableName +")\n"); - matlabSwitchCode.append("\t\t\t\t" + objectTableName + "(" + tableIdxName + "*2+1) = " + objectTableName +"(end);\n"); - matlabSwitchCode.append("\t\t\t\t" + objectTableName +"(end)=[];\n"); +// matlabSwitchCode.append("\t\t\t" + objectTableName + "(" + tableIdxName +") = " + functionCall + ";\n"); + matlabSwitchCode.append("\t\t\t" + tableIdxName + " = " + tableIdxName +" + 1;\n"); + matlabSwitchCode.append("\t\t\t" + objectTableName + "= " + functionCall + objectTableName + ", " + tableIdxName + ");\n"); + matlabSwitchCode.append("\t\t\tif " + tableIdxName + " >= length(" + objectTableName +") %Check to see if pre-allocated memory is exhausted\n"); + matlabSwitchCode.append("\t\t\t\tFieldNames= fieldnames(" + objectTableName +");\n"); + matlabSwitchCode.append("\t\t\t\tfor i=1:length(FieldNames) %Grow structure\n"); + matlabSwitchCode.append("\t\t\t\t\t" + objectTableName + ".(FieldNames{i})(:," + tableIdxName + "*2+1) = 0;\n"); + matlabSwitchCode.append("\t\t\t\tend;\n"); matlabSwitchCode.append("\t\t\tend\n"); - //=============================================================// + //============================================================// // Generate 'Cleanup:' code (will replace the $(CLEANUP) tag) // - //=============================================================// - matlabCleanupCode.append(objectTableName + "(" + tableIdxName +":end) = [];\n"); + //============================================================// + matlabCleanupCode.append(objectTableName + "=PruneStructOfArrays(" + objectTableName + "," + tableIdxName +"); %#ok\n" ); + - - //=============================================================================// - // Generate objects saving code code (will replace the $(SAVEOBJECTSCODE) tag) // - //=============================================================================// + //========================================================================// + // Generate objects saving code (will replace the $(SAVEOBJECTSCODE) tag) // + //========================================================================// matlabSaveObjectsCode.append(",'"+objectTableName+"'"); - matlabFunctionsCode.append("%%\n% " + objectName + " read function\n"); + //==========================================================================// + // Generate objects csv export code (will replace the $(EXPORTCSVCODE) tag) // + //==========================================================================// + matlabExportCsvCode.append("\tOPLog2csv(" + objectTableName + ", '"+objectTableName+"', logfile);\n"); +// OPLog2csv(ActuatorCommand, 'ActuatorCommand', logfile) //=================================================================// // Generate functions code (will replace the $(FUNCTIONSCODE) tag) // //=================================================================// - //Generate function description comment - matlabFunctionsCode.append("function [" + objectName + "] = " + functionCall + "\n"); - matlabFunctionsCode.append("\t" + objectName + ".timestamp = timestamp;\n"); + //Generate function description comment + matlabFunctionsCode.append("%%\n% " + objectName + " read function\n"); + + matlabFunctionsCode.append("function [" + objectName + "] = " + functionCall + objectTableName + ", " + tableIdxName + ")" + "\n"); + matlabFunctionsCode.append("\t" + objectName + ".timestamp(" + tableIdxName + ")= timestamp;\n"); matlabFunctionsCode.append("\tif " + isSingleInst + "\n"); matlabFunctionsCode.append("\t\theaderSize = 8;\n"); matlabFunctionsCode.append("\telse\n"); - matlabFunctionsCode.append("\t\t" + objectName + ".instanceID = fread(fid, 1, 'uint16');\n"); + matlabFunctionsCode.append("\t\t" + objectName + ".instanceID(" + tableIdxName + ") = (fread(fid, 1, 'uint16'));\n"); matlabFunctionsCode.append("\t\theaderSize = 10;\n"); matlabFunctionsCode.append("\tend\n\n"); @@ -169,14 +182,14 @@ bool UAVObjectGeneratorMatlab::process_object(ObjectInfo* info) type = fieldTypeStrMatlab[info->fields[n]->type]; // Append field if ( info->fields[n]->numElements > 1 ) - funcfields.append("\t" + objectName + "." + info->fields[n]->name + " = double(fread(fid, " + QString::number(info->fields[n]->numElements, 10) + ", '" + type + "'));\n"); + funcfields.append("\t" + objectName + "." + info->fields[n]->name + "(:," + tableIdxName + ") = double(fread(fid, " + QString::number(info->fields[n]->numElements, 10) + ", '" + type + "'));\n"); else - funcfields.append("\t" + objectName + "." + info->fields[n]->name + " = double(fread(fid, 1, '" + type + "'));\n"); + funcfields.append("\t" + objectName + "." + info->fields[n]->name + "(" + tableIdxName + ") = double(fread(fid, 1, '" + type + "'));\n"); } matlabFunctionsCode.append(funcfields); matlabFunctionsCode.append("\t% read CRC\n"); - matlabFunctionsCode.append("\tfread(fid, 1, 'uint8');\n"); + matlabFunctionsCode.append("\tfread(fid, 1, '*uint8');\n"); matlabFunctionsCode.append("\n\n"); diff --git a/ground/uavobjgenerator/generators/matlab/uavobjectgeneratormatlab.h b/ground/uavobjgenerator/generators/matlab/uavobjectgeneratormatlab.h index b86b001a5..c4025a4f4 100644 --- a/ground/uavobjgenerator/generators/matlab/uavobjectgeneratormatlab.h +++ b/ground/uavobjgenerator/generators/matlab/uavobjectgeneratormatlab.h @@ -40,6 +40,7 @@ private: QString matlabSwitchCode; QString matlabCleanupCode; QString matlabSaveObjectsCode; + QString matlabExportCsvCode; QString matlabFunctionsCode; QStringList fieldTypeStrMatlab; diff --git a/hardware/Production/Spektrum Adapter SMD/Assembly/Spektrum Adapter SMD 3D Top.pdf b/hardware/Production/Spektrum Adapter SMD/Assembly/Spektrum Adapter SMD 3D Top.pdf new file mode 100644 index 000000000..dcb64a2e3 Binary files /dev/null and b/hardware/Production/Spektrum Adapter SMD/Assembly/Spektrum Adapter SMD 3D Top.pdf differ diff --git a/hardware/Production/Spektrum Adapter SMD/Assembly/Spektrum Adapter SMD Assembly.pdf b/hardware/Production/Spektrum Adapter SMD/Assembly/Spektrum Adapter SMD Assembly.pdf new file mode 100644 index 000000000..780cbb822 Binary files /dev/null and b/hardware/Production/Spektrum Adapter SMD/Assembly/Spektrum Adapter SMD Assembly.pdf differ diff --git a/hardware/Production/Spektrum Adapter SMD/BOM/Spektrum Adapter BOM.xls b/hardware/Production/Spektrum Adapter SMD/BOM/Spektrum Adapter BOM.xls new file mode 100644 index 000000000..7f09125e7 Binary files /dev/null and b/hardware/Production/Spektrum Adapter SMD/BOM/Spektrum Adapter BOM.xls differ diff --git a/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD-macro.APR_LIB b/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD-macro.APR_LIB new file mode 100644 index 000000000..e69de29bb diff --git a/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.EXTREP b/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.EXTREP new file mode 100644 index 000000000..a4280a266 --- /dev/null +++ b/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.EXTREP @@ -0,0 +1,18 @@ +------------------------------------------------------------------------------------------ +Gerber File Extension Report For: Spektrum Adapter SMD.GBR 2/11/2011 2:24:15 PM +------------------------------------------------------------------------------------------ + + +------------------------------------------------------------------------------------------ +Layer Extension Layer Description +------------------------------------------------------------------------------------------ +.GTL Top Layer +.GPB Bottom Pad Master +.GPT Top Pad Master +.GTP Top Paste +.GTS Top Solder +.GM5 Board Dimensions +.GM13 Mechanical 13 +.GM15 Mechanical 15 +.GKO Keep-Out Layer +------------------------------------------------------------------------------------------ diff --git a/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.GKO b/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.GKO new file mode 100644 index 000000000..d73f0985b --- /dev/null +++ b/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.GKO @@ -0,0 +1,26 @@ +%FSLAX25Y25*% +%MOIN*% +G70* +G01* +G75* +G04 Layer_Color=16711935* +%ADD10C,0.01000*% +%ADD11R,0.07087X0.04724*% +%ADD12R,0.06102X0.02362*% +%ADD13R,0.04331X0.05512*% +%ADD14R,0.03543X0.02559*% +%ADD15R,0.03543X0.03150*% +%ADD16R,0.06299X0.02756*% +%ADD17R,0.07480X0.04331*% +%ADD18R,0.02047X0.06510*% +%ADD19R,0.02900X0.06510*% +%ADD20R,0.07488X0.05126*% +%ADD21R,0.06504X0.02764*% +%ADD22R,0.05131X0.06312*% +%ADD23R,0.04143X0.03159*% +%ADD24R,0.04343X0.03950*% +%ADD25R,0.07099X0.03556*% +%ADD26R,0.08280X0.05131*% +%ADD27C,0.00100*% +%ADD28C,0.00394*% +M02* diff --git a/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.GM13 b/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.GM13 new file mode 100644 index 000000000..c967bf3db --- /dev/null +++ b/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.GM13 @@ -0,0 +1,59 @@ +%FSLAX25Y25*% +%MOIN*% +G70* +G01* +G75* +G04 Layer_Color=16711935* +%ADD10C,0.01000*% +%ADD11R,0.07087X0.04724*% +%ADD12R,0.06102X0.02362*% +%ADD13R,0.04331X0.05512*% +%ADD14R,0.03543X0.02559*% +%ADD15R,0.03543X0.03150*% +%ADD16R,0.06299X0.02756*% +%ADD17R,0.07480X0.04331*% +%ADD18R,0.02047X0.06510*% +%ADD19R,0.02900X0.06510*% +%ADD20R,0.07488X0.05126*% +%ADD21R,0.06504X0.02764*% +%ADD22R,0.05131X0.06312*% +%ADD23R,0.04143X0.03159*% +%ADD24R,0.04343X0.03950*% +%ADD25R,0.07099X0.03556*% +%ADD26R,0.08280X0.05131*% +%ADD27C,0.00100*% +%ADD28C,0.00394*% +D28* +X32669Y2646D02* +X41331D01* +X32669Y8354D02* +X41331D01* +Y2646D02* +Y8354D01* +X32669Y2646D02* +Y8354D01* +X41843Y10148D02* +Y22352D01* +X34757Y10148D02* +Y22352D01* +Y10148D02* +X41843D01* +X34757Y22352D02* +X41843D01* +X34169Y30354D02* +X42831D01* +X34169Y24646D02* +X42831D01* +X34169D02* +Y30354D01* +X42831Y24646D02* +Y30354D01* +X26630Y22555D02* +X30370D01* +X26630Y29445D02* +X30370D01* +X26630Y22555D02* +Y29445D01* +X30370Y22555D02* +Y29445D01* +M02* diff --git a/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.GM15 b/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.GM15 new file mode 100644 index 000000000..a5d6b3197 --- /dev/null +++ b/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.GM15 @@ -0,0 +1,75 @@ +%FSLAX25Y25*% +%MOIN*% +G70* +G01* +G75* +G04 Layer_Color=32768* +%ADD10C,0.01000*% +%ADD11R,0.07087X0.04724*% +%ADD12R,0.06102X0.02362*% +%ADD13R,0.04331X0.05512*% +%ADD14R,0.03543X0.02559*% +%ADD15R,0.03543X0.03150*% +%ADD16R,0.06299X0.02756*% +%ADD17R,0.07480X0.04331*% +%ADD18R,0.02047X0.06510*% +%ADD19R,0.02900X0.06510*% +%ADD20R,0.07488X0.05126*% +%ADD21R,0.06504X0.02764*% +%ADD22R,0.05131X0.06312*% +%ADD23R,0.04143X0.03159*% +%ADD24R,0.04343X0.03950*% +%ADD25R,0.07099X0.03556*% +%ADD26R,0.08280X0.05131*% +%ADD27C,0.00100*% +%ADD28C,0.00394*% +D28* +X37000Y3531D02* +Y7468D01* +X35032Y5500D02* +X38969D01* +X31488Y2350D02* +X42512D01* +X31488Y8650D02* +X42512D01* +Y2350D02* +Y8650D01* +X31488Y2350D02* +Y8650D01* +X45190Y9754D02* +Y22746D01* +X31410Y9754D02* +Y22746D01* +Y9754D02* +X45190D01* +X31410Y22746D02* +X45190D01* +X36331Y16250D02* +X40268D01* +X38300Y14281D02* +Y18218D01* +X38500Y25532D02* +Y29469D01* +X36531Y27500D02* +X40468D01* +X32988Y30650D02* +X44012D01* +X32988Y24350D02* +X44012D01* +X32988D02* +Y30650D01* +X44012Y24350D02* +Y30650D01* +X26335Y21276D02* +X30665D01* +X26335Y30724D02* +X30665D01* +X26335Y21276D02* +Y30724D01* +X30665Y21276D02* +Y30724D01* +X28500Y24130D02* +Y27870D01* +X26630Y26000D02* +X30370D01* +M02* diff --git a/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.GM5 b/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.GM5 new file mode 100644 index 000000000..494a59c91 --- /dev/null +++ b/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.GM5 @@ -0,0 +1,33 @@ +%FSLAX25Y25*% +%MOIN*% +G70* +G01* +G75* +G04 Layer_Color=16711935* +%ADD10C,0.01000*% +%ADD11R,0.07087X0.04724*% +%ADD12R,0.06102X0.02362*% +%ADD13R,0.04331X0.05512*% +%ADD14R,0.03543X0.02559*% +%ADD15R,0.03543X0.03150*% +%ADD16R,0.06299X0.02756*% +%ADD17R,0.07480X0.04331*% +%ADD18R,0.02047X0.06510*% +%ADD19R,0.02900X0.06510*% +%ADD20R,0.07488X0.05126*% +%ADD21R,0.06504X0.02764*% +%ADD22R,0.05131X0.06312*% +%ADD23R,0.04143X0.03159*% +%ADD24R,0.04343X0.03950*% +%ADD25R,0.07099X0.03556*% +%ADD26R,0.08280X0.05131*% +%ADD27C,0.00100*% +D27* +X0Y0D02* +Y34000D01* +Y0D02* +X69500D01* +Y34000D01* +X0D02* +X69500D01* +M02* diff --git a/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.GPB b/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.GPB new file mode 100644 index 000000000..32fdc9c47 --- /dev/null +++ b/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.GPB @@ -0,0 +1,17 @@ +%FSLAX25Y25*% +%MOIN*% +G70* +G01* +G75* +G04 Layer_Color=255* +%ADD10C,0.01000*% +%ADD11R,0.07087X0.04724*% +%ADD12R,0.06102X0.02362*% +%ADD13R,0.04331X0.05512*% +%ADD14R,0.03543X0.02559*% +%ADD15R,0.03543X0.03150*% +%ADD16R,0.06299X0.02756*% +%ADD17R,0.07480X0.04331*% +%ADD18R,0.02047X0.06510*% +%ADD19R,0.02900X0.06510*% +M02* diff --git a/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.GPT b/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.GPT new file mode 100644 index 000000000..12005c520 --- /dev/null +++ b/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.GPT @@ -0,0 +1,67 @@ +%FSLAX25Y25*% +%MOIN*% +G70* +G01* +G75* +%ADD10C,0.01000*% +%ADD11R,0.07087X0.04724*% +%ADD12R,0.06102X0.02362*% +%ADD13R,0.04331X0.05512*% +%ADD14R,0.03543X0.02559*% +%ADD15R,0.03543X0.03150*% +%ADD16R,0.06299X0.02756*% +%ADD17R,0.07480X0.04331*% +%ADD18R,0.02047X0.06510*% +%ADD19R,0.02900X0.06510*% +D11* +X65747Y28274D02* +D03* +Y6226D02* +D03* +D12* +X50590Y23155D02* +D03* +Y15281D02* +D03* +Y11344D02* +D03* +Y19218D02* +D03* +D13* +X39953Y5500D02* +D03* +X34047D02* +D03* +X35547Y27500D02* +D03* +X41453D02* +D03* +D14* +X43024Y12510D02* +D03* +Y16250D02* +D03* +Y19990D02* +D03* +X33576D02* +D03* +Y12510D02* +D03* +D15* +X28500Y23244D02* +D03* +Y28756D02* +D03* +D16* +X21500Y22906D02* +D03* +Y17000D02* +D03* +Y11095D02* +D03* +D17* +X6500Y30583D02* +D03* +Y3417D02* +D03* +M02* diff --git a/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.GTL b/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.GTL new file mode 100644 index 000000000..533d704e9 --- /dev/null +++ b/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.GTL @@ -0,0 +1,486 @@ +%FSLAX25Y25*% +%MOIN*% +G70* +G01* +G75* +G04 Layer_Physical_Order=1* +G04 Layer_Color=255* +%ADD10C,0.01000*% +%ADD11R,0.07087X0.04724*% +%ADD12R,0.06102X0.02362*% +%ADD13R,0.04331X0.05512*% +%ADD14R,0.03543X0.02559*% +%ADD15R,0.03543X0.03150*% +%ADD16R,0.06299X0.02756*% +%ADD17R,0.07480X0.04331*% +%ADD18R,0.02047X0.06510*% +%ADD19R,0.02900X0.06510*% +G36* +X69000Y31436D02* +X61404D01* +Y25111D01* +X69000D01* +Y9389D01* +X61404D01* +Y3064D01* +X69000D01* +Y500D01* +X11040D01* +Y6383D01* +X1960D01* +Y500D01* +X500D01* +Y33600D01* +X1960D01* +Y33600D01* +Y33548D01* +X1960Y33176D01* +X1960Y33176D01* +X1960D01* +Y27617D01* +X11040D01* +Y33176D01* +X11040Y33176D01* +D01* +D01* +X11040Y33548D01* +D01* +X11092Y33600D01* +X18825D01* +X18892Y33544D01* +X19098Y33046D01* +X12376Y26324D01* +X12214Y26126D01* +X12093Y25900D01* +X12019Y25655D01* +X11994Y25400D01* +Y15700D01* +X12019Y15445D01* +X12093Y15200D01* +X12214Y14974D01* +X12214Y14974D01* +X12214Y14974D01* +X12376Y14776D01* +X14192Y12961D01* +Y12956D01* +Y12956D01* +X14239Y12913D01* +X15901Y11251D01* +X15901Y11251D01* +X15900Y11250D01* +X15929Y11223D01* +X16982Y10171D01* +X16982Y10171D01* +X17180Y10008D01* +X17406Y9888D01* +X17550Y9844D01* +Y8917D01* +X25450D01* +Y13272D01* +X19792D01* +X19728Y13279D01* +Y13279D01* +X19724Y13274D01* +X19144Y13307D01* +X18567Y13405D01* +X18005Y13567D01* +X17464Y13791D01* +X16952Y14074D01* +X16475Y14413D01* +X16098Y14749D01* +X16041Y14806D01* +X16041Y14806D01* +X16041Y14806D01* +X14606Y16241D01* +Y24859D01* +X20741Y30994D01* +X38487D01* +Y23944D01* +X40646D01* +Y22070D01* +X40453D01* +Y17911D01* +X44932D01* +Y17499D01* +X44957Y17244D01* +X45032Y16999D01* +X45152Y16773D01* +X45315Y16575D01* +X45946Y15944D01* +X45888Y15347D01* +X45586Y15145D01* +X45100Y14906D01* +X44588Y14731D01* +X44057Y14626D01* +X43522Y14591D01* +X43516Y14596D01* +Y14596D01* +X43453Y14589D01* +X40453D01* +Y10430D01* +X45596D01* +Y11360D01* +X45716Y11424D01* +X45914Y11586D01* +X46547Y12220D01* +X46582Y12250D01* +X46580Y12252D01* +X46886Y12558D01* +X47159Y12791D01* +X47514Y13009D01* +X47899Y13169D01* +X48304Y13266D01* +X48715Y13298D01* +X48720Y13294D01* +Y13294D01* +X48783Y13300D01* +X54441D01* +Y17237D01* +Y18024D01* +X54644Y18132D01* +X54842Y18295D01* +X55303Y18756D01* +X55331Y18780D01* +X55329Y18782D01* +X55329Y18782D01* +X57015Y20467D01* +X57037Y20488D01* +X57036Y20489D01* +X57036Y20489D01* +X57624Y21076D01* +X57624Y21076D01* +X57786Y21274D01* +X57907Y21500D01* +X57981Y21745D01* +X58006Y22000D01* +X58006Y22000D01* +Y25600D01* +X57981Y25855D01* +X57907Y26100D01* +X57786Y26326D01* +X57624Y26524D01* +X56024Y28124D01* +X55826Y28286D01* +X55600Y28407D01* +X55355Y28481D01* +X55100Y28506D01* +X50441D01* +X45902Y33046D01* +X46131Y33600D01* +X69000D01* +Y31436D01* +D02* +G37* +%LPC*% +G36* +X31072Y25619D02* +X25928D01* +Y25084D01* +X25450D01* +Y25084D01* +X17550D01* +Y20728D01* +X23208D01* +X23272Y20721D01* +Y20721D01* +X23272Y20722D01* +X23409Y20704D01* +X23536Y20651D01* +X23641Y20571D01* +X23645Y20567D01* +X23645Y20567D01* +Y20567D01* +X23645Y20567D01* +X23912Y20300D01* +X23929Y20280D01* +X23930Y20282D01* +X23930Y20282D01* +X30500Y13712D01* +X30500Y13712D01* +D01* +X30532Y13680D01* +X30715Y13457D01* +X30872Y13162D01* +X30969Y12842D01* +X31002Y12514D01* +X30998Y12510D01* +X30998D01* +X31004Y12446D01* +Y10430D01* +X31393D01* +Y9056D01* +X31082D01* +Y1944D01* +X37013D01* +Y9056D01* +X35907D01* +Y10430D01* +X36147D01* +Y14589D01* +X33317D01* +X32379Y15528D01* +X32349Y15562D01* +X32347Y15560D01* +X32347Y15560D01* +X27592Y20315D01* +X27821Y20869D01* +X28633D01* +X28697Y20863D01* +Y20863D01* +X28701Y20866D01* +X29150Y20837D01* +X29596Y20748D01* +X30026Y20602D01* +X30090Y20571D01* +X30096Y20560D01* +X30258Y20362D01* +X30456Y20199D01* +X30531Y20159D01* +X30531Y20159D01* +X30531D01* +X30531D01* +Y20159D01* +Y20159D01* +X30532Y20159D01* +X30532Y20159D01* +X30773Y19974D01* +X30958Y19733D01* +X31004Y19623D01* +Y17911D01* +X36147D01* +Y22070D01* +X33147D01* +X33084Y22076D01* +Y22076D01* +X33077Y22071D01* +X32789Y22109D01* +X32516Y22222D01* +X32317Y22375D01* +X32285Y22407D01* +X32285Y22407D01* +X32285Y22407D01* +X31290Y23401D01* +X31290Y23402D01* +X31291Y23403D01* +X31273Y23418D01* +X31072Y23620D01* +Y25619D01* +D02* +G37* +%LPD*% +D10* +X15118Y13882D02* +G03* +X19728Y11972I4611J4611D01* +G01* +X16825Y12175D02* +G03* +X19728Y10972I2903J2903D01* +G01* +X17906Y11095D02* +G03* +X19042Y11642I0J1453D01* +G01* +Y10547D02* +G03* +X17906Y11095I-1136J-906D01* +G01* +X24569Y21490D02* +G03* +X23272Y22028I-1297J-1297D01* +G01* +X24150Y22906D02* +G03* +X24854Y21205I2404J0D01* +G01* +X32073Y20771D02* +G03* +X28697Y22169I-3377J-3377D01* +G01* +X30366Y22478D02* +G03* +X28697Y23169I-1670J-1670D01* +G01* +X32304Y12510D02* +G03* +X31423Y14636I-3007J0D01* +G01* +X31896Y20873D02* +G03* +X32882Y20743I649J1124D01* +G01* +X32331Y19788D02* +G03* +X31182Y21285I-2382J-638D01* +G01* +X31361Y21483D02* +G03* +X33084Y20770I1723J1723D01* +G01* +X32304Y19990D02* +G03* +X31915Y20929I-1328J0D01* +G01* +X46238Y18926D02* +G03* +X43872Y19297I-1438J-1438D01* +G01* +X45268Y19896D02* +G03* +X43416Y20186I-1126J-1126D01* +G01* +X45174Y19990D02* +G03* +X44117Y19493I0J-1372D01* +G01* +Y20487D02* +G03* +X45174Y19990I1057J875D01* +G01* +X43516Y13289D02* +G03* +X47363Y14883I0J5440D01* +G01* +X43516Y12289D02* +G03* +X45656Y13175I0J3025D01* +G01* +X44990Y12510D02* +G03* +X44161Y12071I0J-1003D01* +G01* +Y12948D02* +G03* +X44990Y12510I829J564D01* +G01* +X52460Y19900D02* +G03* +X56113Y21413I0J5166D01* +G01* +X52460Y18900D02* +G03* +X54405Y19705I0J2752D01* +G01* +X53918Y19218D02* +G03* +X52982Y18781I0J-1221D01* +G01* +Y19656D02* +G03* +X53918Y19218I936J784D01* +G01* +X47107Y16631D02* +G03* +X48720Y15963I1613J1613D01* +G01* +X48039Y15281D02* +G03* +X47743Y15994I-1008J0D01* +G01* +X48720Y14600D02* +G03* +X45922Y13442I0J-3957D01* +G01* +X50590Y11344D02* +X50645Y11400D01* +X46239Y17499D02* +X48456Y15281D01* +X50390D01* +X46239Y17499D02* +Y18925D01* +X45174Y19990D02* +X46239Y18925D01* +X48256Y15281D02* +X50390D01* +X47762D02* +X50390D01* +X17906Y11095D02* +X21500D01* +X43024Y19990D02* +X45174D01* +X29050Y23794D02* +X32854Y19990D01* +X33549Y12510D02* +X33576D01* +X23154Y22906D02* +X33549Y12510D01* +X21500Y22906D02* +X23154D01* +X44990Y12510D02* +X47762Y15281D01* +X43024Y12510D02* +X44990D01* +X13300Y15700D02* +X17906Y11095D01* +X13300Y15700D02* +Y25400D01* +X50590Y19218D02* +X53918D01* +X13300Y25400D02* +X20200Y32300D01* +X44800D01* +X53918Y19218D02* +X56700Y22000D01* +Y25600D01* +X44800Y32300D02* +X49900Y27200D01* +X55100D01* +X56700Y25600D01* +D11* +X65747Y28274D02* +D03* +Y6226D02* +D03* +D12* +X50590Y23155D02* +D03* +Y15281D02* +D03* +Y11344D02* +D03* +Y19218D02* +D03* +D13* +X39953Y5500D02* +D03* +X34047D02* +D03* +X35547Y27500D02* +D03* +X41453D02* +D03* +D14* +X43024Y12510D02* +D03* +Y16250D02* +D03* +Y19990D02* +D03* +X33576D02* +D03* +Y12510D02* +D03* +D15* +X28500Y23244D02* +D03* +Y28756D02* +D03* +D16* +X21500Y22906D02* +D03* +Y17000D02* +D03* +Y11095D02* +D03* +D17* +X6500Y30583D02* +D03* +Y3417D02* +D03* +D18* +X42476Y24245D02* +D03* +D19* +X33650Y9255D02* +D03* +M02* diff --git a/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.GTP b/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.GTP new file mode 100644 index 000000000..12005c520 --- /dev/null +++ b/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.GTP @@ -0,0 +1,67 @@ +%FSLAX25Y25*% +%MOIN*% +G70* +G01* +G75* +%ADD10C,0.01000*% +%ADD11R,0.07087X0.04724*% +%ADD12R,0.06102X0.02362*% +%ADD13R,0.04331X0.05512*% +%ADD14R,0.03543X0.02559*% +%ADD15R,0.03543X0.03150*% +%ADD16R,0.06299X0.02756*% +%ADD17R,0.07480X0.04331*% +%ADD18R,0.02047X0.06510*% +%ADD19R,0.02900X0.06510*% +D11* +X65747Y28274D02* +D03* +Y6226D02* +D03* +D12* +X50590Y23155D02* +D03* +Y15281D02* +D03* +Y11344D02* +D03* +Y19218D02* +D03* +D13* +X39953Y5500D02* +D03* +X34047D02* +D03* +X35547Y27500D02* +D03* +X41453D02* +D03* +D14* +X43024Y12510D02* +D03* +Y16250D02* +D03* +Y19990D02* +D03* +X33576D02* +D03* +Y12510D02* +D03* +D15* +X28500Y23244D02* +D03* +Y28756D02* +D03* +D16* +X21500Y22906D02* +D03* +Y17000D02* +D03* +Y11095D02* +D03* +D17* +X6500Y30583D02* +D03* +Y3417D02* +D03* +M02* diff --git a/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.GTS b/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.GTS new file mode 100644 index 000000000..ff85a5b1f --- /dev/null +++ b/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.GTS @@ -0,0 +1,75 @@ +%FSLAX25Y25*% +%MOIN*% +G70* +G01* +G75* +G04 Layer_Color=8388736* +%ADD10C,0.01000*% +%ADD11R,0.07087X0.04724*% +%ADD12R,0.06102X0.02362*% +%ADD13R,0.04331X0.05512*% +%ADD14R,0.03543X0.02559*% +%ADD15R,0.03543X0.03150*% +%ADD16R,0.06299X0.02756*% +%ADD17R,0.07480X0.04331*% +%ADD18R,0.02047X0.06510*% +%ADD19R,0.02900X0.06510*% +%ADD20R,0.07488X0.05126*% +%ADD21R,0.06504X0.02764*% +%ADD22R,0.05131X0.06312*% +%ADD23R,0.04143X0.03159*% +%ADD24R,0.04343X0.03950*% +%ADD25R,0.07099X0.03556*% +%ADD26R,0.08280X0.05131*% +D20* +X65747Y28274D02* +D03* +Y6226D02* +D03* +D21* +X50590Y23155D02* +D03* +Y15281D02* +D03* +Y11344D02* +D03* +Y19218D02* +D03* +D22* +X39953Y5500D02* +D03* +X34047D02* +D03* +X35547Y27500D02* +D03* +X41453D02* +D03* +D23* +X43024Y12510D02* +D03* +Y16250D02* +D03* +Y19990D02* +D03* +X33576D02* +D03* +Y12510D02* +D03* +D24* +X28500Y23244D02* +D03* +Y28756D02* +D03* +D25* +X21500Y22906D02* +D03* +Y17000D02* +D03* +Y11095D02* +D03* +D26* +X6500Y30583D02* +D03* +Y3417D02* +D03* +M02* diff --git a/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.REP b/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.REP new file mode 100644 index 000000000..48a789e17 --- /dev/null +++ b/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.REP @@ -0,0 +1,141 @@ +************************************************************* +FileName = Spektrum Adapter SMD.GBR +AutoAperture = True +************************************************************* +Generating : Top Layer + File : Spektrum Adapter SMD.GTL + + Adding Layer : Top Layer + + Adding Layer : Multi-Layer + + +Used DCodes : + D10 + D11 + D12 + D13 + D14 + D15 + D16 + D17 + D18 + D19 +************************************************************* + +************************************************************* +Generating : Bottom Pad Master + File : Spektrum Adapter SMD.GPB + + Adding Layer : Bottom Layer + + Adding Layer : Multi-Layer + + +Used DCodes : +************************************************************* + +************************************************************* +Generating : Top Pad Master + File : Spektrum Adapter SMD.GPT + + Adding Layer : Top Layer + + Adding Layer : Multi-Layer + + +Used DCodes : + D11 + D12 + D13 + D14 + D15 + D16 + D17 +************************************************************* + +************************************************************* +Generating : Top Paste + File : Spektrum Adapter SMD.GTP + + Adding Layer : Top Paste + + Adding Layer : Top Layer + + Adding Layer : Multi-Layer + + +Used DCodes : + D11 + D12 + D13 + D14 + D15 + D16 + D17 +************************************************************* + +************************************************************* +Generating : Top Solder + File : Spektrum Adapter SMD.GTS + + Adding Layer : Top Solder + + Adding Layer : Top Layer + + Adding Layer : Multi-Layer + + +Used DCodes : + D20 + D21 + D22 + D23 + D24 + D25 + D26 +************************************************************* + +************************************************************* +Generating : Board Dimensions + File : Spektrum Adapter SMD.GM5 + + Adding Layer : Board Dimensions + + +Used DCodes : + D27 +************************************************************* + +************************************************************* +Generating : Mechanical 13 + File : Spektrum Adapter SMD.GM13 + + Adding Layer : Mechanical 13 + + +Used DCodes : + D28 +************************************************************* + +************************************************************* +Generating : Mechanical 15 + File : Spektrum Adapter SMD.GM15 + + Adding Layer : Mechanical 15 + + +Used DCodes : + D28 +************************************************************* + +************************************************************* +Generating : Keep-Out Layer + File : Spektrum Adapter SMD.GKO + + Adding Layer : Keep-Out Layer + + +Used DCodes : +************************************************************* + diff --git a/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.RUL b/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.RUL new file mode 100644 index 000000000..fb8f7eda3 --- /dev/null +++ b/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.RUL @@ -0,0 +1,5 @@ +DRC Rules Export File for PCB: C:\Users\David\Documents\OP-WIP\trunk\hardware\production\Spektrum Adapter SMD\Spektrum Adapter SMD.PcbDoc +RuleKind=ShortCircuit|RuleName=ShortCircuit|Scope=Board|Allowed=0 +RuleKind=Clearance|RuleName=Clearance|Scope=Board|Minimum=8.00 +RuleKind=Width|RuleName=Width|Scope=Board|Minimum=10.00 +RuleKind=SolderMaskExpansion|RuleName=SolderMaskExpansion|Scope=Board|Minimum=4.00 diff --git a/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.apr b/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.apr new file mode 100644 index 000000000..15665e02f --- /dev/null +++ b/hardware/Production/Spektrum Adapter SMD/Gerbers/Spektrum Adapter SMD.apr @@ -0,0 +1,19 @@ +D10 ROUNDED 10.000 10.000 0.000 LINE 0.000 +D11 RECTANGULAR 70.866 47.244 0.000 FLASH 0.000 +D12 RECTANGULAR 61.024 23.622 0.000 FLASH 0.000 +D13 RECTANGULAR 55.118 43.307 0.000 FLASH 90.000 +D14 RECTANGULAR 25.591 35.433 0.000 FLASH 270.000 +D15 RECTANGULAR 35.433 31.496 0.000 FLASH 180.000 +D16 RECTANGULAR 27.559 62.992 0.000 FLASH 90.000 +D17 RECTANGULAR 43.307 74.803 0.000 FLASH 90.000 +D18 RECTANGULAR 20.473 65.098 0.000 FLASH 0.000 +D19 RECTANGULAR 29.000 65.098 0.000 FLASH 0.000 +D20 RECTANGULAR 74.882 51.260 0.000 FLASH 0.000 +D21 RECTANGULAR 65.039 27.638 0.000 FLASH 0.000 +D22 RECTANGULAR 63.118 51.307 0.000 FLASH 90.000 +D23 RECTANGULAR 31.591 41.433 0.000 FLASH 270.000 +D24 RECTANGULAR 43.433 39.496 0.000 FLASH 180.000 +D25 RECTANGULAR 35.559 70.992 0.000 FLASH 90.000 +D26 RECTANGULAR 51.307 82.803 0.000 FLASH 90.000 +D27 ROUNDED 1.000 1.000 0.000 LINE 0.000 +D28 ROUNDED 3.937 3.937 0.000 LINE 0.000 diff --git a/hardware/Production/Spektrum Adapter SMD/Gerbers/Status Report.Txt b/hardware/Production/Spektrum Adapter SMD/Gerbers/Status Report.Txt new file mode 100644 index 000000000..3a2ff231d --- /dev/null +++ b/hardware/Production/Spektrum Adapter SMD/Gerbers/Status Report.Txt @@ -0,0 +1,21 @@ +Output: Gerber Files +Type : Gerber +From : Variant [[No Variations]] of Project [Spektrum Adapter SMD.PrjPCB] + Generated File[Spektrum Adapter SMD.GTL] + Generated File[Spektrum Adapter SMD.GPB] + Generated File[Spektrum Adapter SMD.GPT] + Generated File[Spektrum Adapter SMD.GTP] + Generated File[Spektrum Adapter SMD.GTS] + Generated File[Spektrum Adapter SMD.GM5] + Generated File[Spektrum Adapter SMD.GM13] + Generated File[Spektrum Adapter SMD.GM15] + Generated File[Spektrum Adapter SMD.GKO] + Generated File[Spektrum Adapter SMD.RUL] + Generated File[Spektrum Adapter SMD.EXTREP] + Generated File[Spektrum Adapter SMD.REP] + + +Files Generated : 12 +Documents Printed : 0 + +Finished Output Generation At 2:24:15 PM On 2/11/2011 diff --git a/hardware/Production/Spektrum Adapter SMD/Spektrum Adapter SMD Schematic.pdf b/hardware/Production/Spektrum Adapter SMD/Spektrum Adapter SMD Schematic.pdf new file mode 100644 index 000000000..2faa2b5a0 Binary files /dev/null and b/hardware/Production/Spektrum Adapter SMD/Spektrum Adapter SMD Schematic.pdf differ diff --git a/hardware/Production/Spektrum Adapter SMD/Spektrum Adapter SMD.PcbDoc b/hardware/Production/Spektrum Adapter SMD/Spektrum Adapter SMD.PcbDoc new file mode 100644 index 000000000..fe3ca7127 Binary files /dev/null and b/hardware/Production/Spektrum Adapter SMD/Spektrum Adapter SMD.PcbDoc differ diff --git a/hardware/Production/Spektrum Adapter SMD/Spektrum Adapter SMD.PrjPCB b/hardware/Production/Spektrum Adapter SMD/Spektrum Adapter SMD.PrjPCB new file mode 100644 index 000000000..4cc1642b8 --- /dev/null +++ b/hardware/Production/Spektrum Adapter SMD/Spektrum Adapter SMD.PrjPCB @@ -0,0 +1,1084 @@ +[Design] +Version=1.0 +HierarchyMode=0 +ChannelRoomNamingStyle=0 +OutputPath=Project Outputs for Spektrum Adapter SMD +LogFolderPath= +ReleasesFolder= +ReleaseVaultGUID= +ReleaseVaultName= +ChannelDesignatorFormatString=$Component_$RoomName +ChannelRoomLevelSeperator=_ +OpenOutputs=1 +ArchiveProject=0 +TimestampOutput=0 +SeparateFolders=0 +TemplateLocationPath= +PinSwapBy_Netlabel=1 +PinSwapBy_Pin=1 +AllowPortNetNames=0 +AllowSheetEntryNetNames=1 +AppendSheetNumberToLocalNets=0 +NetlistSinglePinNets=0 +DefaultConfiguration= +UserID=0xFFFFFFFF +DefaultPcbProtel=1 +DefaultPcbPcad=0 +ReorderDocumentsOnCompile=1 +NameNetsHierarchically=0 +PowerPortNamesTakePriority=0 +PushECOToAnnotationFile=1 +DItemRevisionGUID= +ReportSuppressedErrorsInMessages=0 + +[Document1] +DocumentPath=..\Altium\OpenPilot.SchLib +AnnotationEnabled=1 +AnnotateStartValue=1 +AnnotationIndexControlEnabled=0 +AnnotateSuffix= +AnnotateScope=All +AnnotateOrder=-1 +DoLibraryUpdate=1 +DoDatabaseUpdate=1 +ClassGenCCAutoEnabled=1 +ClassGenCCAutoRoomEnabled=1 +ClassGenNCAutoScope=None +DItemRevisionGUID= +GenerateClassCluster=0 + +[Document2] +DocumentPath=..\Altium\OpenPilot.PcbLib +AnnotationEnabled=1 +AnnotateStartValue=1 +AnnotationIndexControlEnabled=0 +AnnotateSuffix= +AnnotateScope=All +AnnotateOrder=-1 +DoLibraryUpdate=1 +DoDatabaseUpdate=1 +ClassGenCCAutoEnabled=1 +ClassGenCCAutoRoomEnabled=1 +ClassGenNCAutoScope=None +DItemRevisionGUID= +GenerateClassCluster=0 + +[Document3] +DocumentPath=Spektrum Adapter SMD.SchDoc +AnnotationEnabled=1 +AnnotateStartValue=1 +AnnotationIndexControlEnabled=0 +AnnotateSuffix= +AnnotateScope=All +AnnotateOrder=-1 +DoLibraryUpdate=1 +DoDatabaseUpdate=1 +ClassGenCCAutoEnabled=1 +ClassGenCCAutoRoomEnabled=0 +ClassGenNCAutoScope=None +DItemRevisionGUID= +GenerateClassCluster=0 + +[Document4] +DocumentPath=Spektrum Adapter SMD.PcbDoc +AnnotationEnabled=1 +AnnotateStartValue=1 +AnnotationIndexControlEnabled=0 +AnnotateSuffix= +AnnotateScope=All +AnnotateOrder=-1 +DoLibraryUpdate=1 +DoDatabaseUpdate=1 +ClassGenCCAutoEnabled=1 +ClassGenCCAutoRoomEnabled=1 +ClassGenNCAutoScope=None +DItemRevisionGUID= +GenerateClassCluster=0 + +[GeneratedDocument1] +DocumentPath=Project Outputs for Spektrum Adapter SMD\Spektrum Adapter SMD.EXTREP +DItemRevisionGUID= + +[GeneratedDocument2] +DocumentPath=Project Outputs for Spektrum Adapter SMD\Spektrum Adapter SMD.GKO +DItemRevisionGUID= + +[GeneratedDocument3] +DocumentPath=Project Outputs for Spektrum Adapter SMD\Spektrum Adapter SMD.GM5 +DItemRevisionGUID= + +[GeneratedDocument4] +DocumentPath=Project Outputs for Spektrum Adapter SMD\Spektrum Adapter SMD.GM13 +DItemRevisionGUID= + +[GeneratedDocument5] +DocumentPath=Project Outputs for Spektrum Adapter SMD\Spektrum Adapter SMD.GM15 +DItemRevisionGUID= + +[GeneratedDocument6] +DocumentPath=Project Outputs for Spektrum Adapter SMD\Spektrum Adapter SMD.GPB +DItemRevisionGUID= + +[GeneratedDocument7] +DocumentPath=Project Outputs for Spektrum Adapter SMD\Spektrum Adapter SMD.GPT +DItemRevisionGUID= + +[GeneratedDocument8] +DocumentPath=Project Outputs for Spektrum Adapter SMD\Spektrum Adapter SMD.GTL +DItemRevisionGUID= + +[GeneratedDocument9] +DocumentPath=Project Outputs for Spektrum Adapter SMD\Spektrum Adapter SMD.GTP +DItemRevisionGUID= + +[GeneratedDocument10] +DocumentPath=Project Outputs for Spektrum Adapter SMD\Spektrum Adapter SMD.GTS +DItemRevisionGUID= + +[GeneratedDocument11] +DocumentPath=Project Outputs for Spektrum Adapter SMD\Spektrum Adapter SMD.REP +DItemRevisionGUID= + +[GeneratedDocument12] +DocumentPath=Project Outputs for Spektrum Adapter SMD\Spektrum Adapter SMD.RUL +DItemRevisionGUID= + +[PCBConfiguration1] +ReleaseItemId= +CurrentRevision= +Name=Default Configuration +Variant=[No Variations] +GenerateBOM=0 + +[Generic_SmartPDF] +AutoOpenFile=-1 +AutoOpenOutJob=-1 + +[Generic_SmartPDFSettings] +ProjectMode=0 +ZoomPrecision=50 +AddNetsInformation=0 +AddNetPins=-1 +AddNetNetLabels=-1 +AddNetPorts=-1 +ExportBOM=0 +TemplateFilename=..\Altium\BOM OpenPilot.xlt +TemplateStoreRelative=-1 +PCB_PrintColor=0 +SCH_PrintColor=0 +SCH_ShowNoErc=-1 +SCH_ShowParameter=-1 +SCH_ShowProbes=-1 +SCH_ShowBlankets=-1 +OutputFileName=Spektrum Adapter SMD.SchDoc=C:\Users\David\Documents\SVN\OP-WIP\trunk\hardware\production\Spektrum Adapter SMD\Spektrum Adapter SMD Schematic.pdf +SCH_ExpandLogicalToPhysical=-1 +SCH_VariantName=[No Variations] +SCH_ExpandComponentDesignators=-1 +SCH_ExpandNetlabels=0 +SCH_ExpandPorts=0 +SCH_ExpandSheetNumber=0 +SCH_ExpandDocumentNumber=0 +SCH_HasExpandLogicalToPhysicalSheets=-1 +SaveSettingsToOutJob=0 +SCH_NoERCSymbolsToShow="Thin Cross","Thick Cross","Small Cross",Checkbox,Triangle +SCH_ShowNote=-1 +SCH_ShowNoteCollapsed=-1 + +[OutputGroup1] +Name=Netlist Outputs +Description= +TargetPrinter=Brother HL-2170W +PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1 +OutputType1=CadnetixNetlist +OutputName1=Cadnetix Netlist +OutputDocumentPath1= +OutputVariantName1= +OutputDefault1=0 +OutputType2=CalayNetlist +OutputName2=Calay Netlist +OutputDocumentPath2= +OutputVariantName2= +OutputDefault2=0 +OutputType3=EDIF +OutputName3=EDIF for PCB +OutputDocumentPath3= +OutputVariantName3= +OutputDefault3=0 +OutputType4=EESofNetlist +OutputName4=EESof Netlist +OutputDocumentPath4= +OutputVariantName4= +OutputDefault4=0 +OutputType5=IntergraphNetlist +OutputName5=Intergraph Netlist +OutputDocumentPath5= +OutputVariantName5= +OutputDefault5=0 +OutputType6=MentorBoardStationNetlist +OutputName6=Mentor BoardStation Netlist +OutputDocumentPath6= +OutputVariantName6= +OutputDefault6=0 +OutputType7=MultiWire +OutputName7=MultiWire +OutputDocumentPath7= +OutputVariantName7= +OutputDefault7=0 +OutputType8=OrCadPCB2Netlist +OutputName8=Orcad/PCB2 Netlist +OutputDocumentPath8= +OutputVariantName8= +OutputDefault8=0 +OutputType9=PADSNetlist +OutputName9=PADS ASCII Netlist +OutputDocumentPath9= +OutputVariantName9= +OutputDefault9=0 +OutputType10=Pcad +OutputName10=Pcad for PCB +OutputDocumentPath10= +OutputVariantName10= +OutputDefault10=0 +OutputType11=PCADNetlist +OutputName11=PCAD Netlist +OutputDocumentPath11= +OutputVariantName11= +OutputDefault11=0 +OutputType12=PCADnltNetlist +OutputName12=PCADnlt Netlist +OutputDocumentPath12= +OutputVariantName12= +OutputDefault12=0 +OutputType13=Protel2Netlist +OutputName13=Protel2 Netlist +OutputDocumentPath13= +OutputVariantName13= +OutputDefault13=0 +OutputType14=ProtelNetlist +OutputName14=Protel +OutputDocumentPath14= +OutputVariantName14= +OutputDefault14=0 +OutputType15=RacalNetlist +OutputName15=Racal Netlist +OutputDocumentPath15= +OutputVariantName15= +OutputDefault15=0 +OutputType16=RINFNetlist +OutputName16=RINF Netlist +OutputDocumentPath16= +OutputVariantName16= +OutputDefault16=0 +OutputType17=SciCardsNetlist +OutputName17=SciCards Netlist +OutputDocumentPath17= +OutputVariantName17= +OutputDefault17=0 +OutputType18=SIMetrixNetlist +OutputName18=SIMetrix +OutputDocumentPath18= +OutputVariantName18= +OutputDefault18=0 +OutputType19=SIMPLISNetlist +OutputName19=SIMPLIS +OutputDocumentPath19= +OutputVariantName19= +OutputDefault19=0 +OutputType20=TangoNetlist +OutputName20=Tango Netlist +OutputDocumentPath20= +OutputVariantName20= +OutputDefault20=0 +OutputType21=TelesisNetlist +OutputName21=Telesis Netlist +OutputDocumentPath21= +OutputVariantName21= +OutputDefault21=0 +OutputType22=Verilog +OutputName22=Verilog File +OutputDocumentPath22= +OutputVariantName22= +OutputDefault22=0 +OutputType23=VHDL +OutputName23=VHDL File +OutputDocumentPath23= +OutputVariantName23= +OutputDefault23=0 +OutputType24=WireListNetlist +OutputName24=WireList Netlist +OutputDocumentPath24= +OutputVariantName24= +OutputDefault24=0 +OutputType25=XSpiceNetlist +OutputName25=XSpice Netlist +OutputDocumentPath25= +OutputVariantName25= +OutputDefault25=0 + +[OutputGroup2] +Name=Simulator Outputs +Description= +TargetPrinter=Brother HL-2170W +PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1 +OutputType1=AdvSimNetlist +OutputName1=Mixed Sim +OutputDocumentPath1= +OutputVariantName1= +OutputDefault1=0 +OutputType2=SIMetrix_Sim +OutputName2=SIMetrix +OutputDocumentPath2= +OutputVariantName2= +OutputDefault2=0 +OutputType3=SIMPLIS_Sim +OutputName3=SIMPLIS +OutputDocumentPath3= +OutputVariantName3= +OutputDefault3=0 + +[OutputGroup3] +Name=Documentation Outputs +Description= +TargetPrinter=Brother HL-2170W +PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1 +OutputType1=Composite +OutputName1=Composite Drawing +OutputDocumentPath1= +OutputVariantName1= +OutputDefault1=0 +PageOptions1=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType2=Logic Analyser Print +OutputName2=Logic Analyser Prints +OutputDocumentPath2= +OutputVariantName2= +OutputDefault2=0 +PageOptions2=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType3=OpenBus Print +OutputName3=OpenBus Prints +OutputDocumentPath3= +OutputVariantName3= +OutputDefault3=0 +PageOptions3=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType4=PCB 3D Print +OutputName4=PCB 3D Prints +OutputDocumentPath4= +OutputVariantName4=[No Variations] +OutputDefault4=0 +PageOptions4=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType5=PCB Print +OutputName5=PCB Prints +OutputDocumentPath5= +OutputVariantName5= +OutputDefault5=0 +PageOptions5=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType6=Schematic Print +OutputName6=Schematic Prints +OutputDocumentPath6= +OutputVariantName6= +OutputDefault6=0 +PageOptions6=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType7=SimView Print +OutputName7=SimView Prints +OutputDocumentPath7= +OutputVariantName7= +OutputDefault7=0 +PageOptions7=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType8=Wave Print +OutputName8=Wave Prints +OutputDocumentPath8= +OutputVariantName8= +OutputDefault8=0 +PageOptions8=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType9=WaveSim Print +OutputName9=WaveSim Prints +OutputDocumentPath9= +OutputVariantName9= +OutputDefault9=0 +PageOptions9=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType10=Assembler Source Print +OutputName10=Assembler Source Prints +OutputDocumentPath10= +OutputVariantName10= +OutputDefault10=0 +PageOptions10=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType11=C Source Print +OutputName11=C Source Prints +OutputDocumentPath11= +OutputVariantName11= +OutputDefault11=0 +PageOptions11=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType12=C/C++ Header Print +OutputName12=C/C++ Header Prints +OutputDocumentPath12= +OutputVariantName12= +OutputDefault12=0 +PageOptions12=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType13=C++ Source Print +OutputName13=C++ Source Prints +OutputDocumentPath13= +OutputVariantName13= +OutputDefault13=0 +PageOptions13=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType14=PCB 3D Video +OutputName14=PCB 3D Video +OutputDocumentPath14= +OutputVariantName14=[No Variations] +OutputDefault14=0 +PageOptions14=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType15=Report Print +OutputName15=Report Prints +OutputDocumentPath15= +OutputVariantName15= +OutputDefault15=0 +PageOptions15=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType16=Software Platform Print +OutputName16=Software Platform Prints +OutputDocumentPath16= +OutputVariantName16= +OutputDefault16=0 +PageOptions16=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType17=VHDL Print +OutputName17=VHDL Prints +OutputDocumentPath17= +OutputVariantName17= +OutputDefault17=0 +PageOptions17=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 + +[OutputGroup4] +Name=Assembly Outputs +Description= +TargetPrinter=Brother HL-2170W +PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1 +OutputType1=Assembly +OutputName1=Assembly Drawings +OutputDocumentPath1= +OutputVariantName1=[No Variations] +OutputDefault1=0 +PageOptions1=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType2=Pick Place +OutputName2=Generates pick and place files +OutputDocumentPath2= +OutputVariantName2=[No Variations] +OutputDefault2=0 +OutputType3=Test Points For Assembly +OutputName3=Test Point Report +OutputDocumentPath3= +OutputVariantName3=[No Variations] +OutputDefault3=0 + +[OutputGroup5] +Name=Fabrication Outputs +Description= +TargetPrinter=Brother HL-2170W +PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1 +OutputType1=ODB +OutputName1=ODB++ Files +OutputDocumentPath1= +OutputVariantName1=[No Variations] +OutputDefault1=0 +OutputType2=NC Drill +OutputName2=NC Drill Files +OutputDocumentPath2= +OutputVariantName2= +OutputDefault2=0 +Configuration2_Name1=OutputConfigurationParameter1 +Configuration2_Item1=BoardEdgeRoutToolDia=2000000|GenerateBoardEdgeRout=False|GenerateDrilledSlotsG85=False|GenerateSeparatePlatedNonPlatedFiles=False|NumberOfDecimals=5|NumberOfUnits=2|OptimizeChangeLocationCommands=True|OriginPosition=Relative|Record=DrillView|Units=Imperial|ZeroesMode=SuppressTrailingZeroes +OutputType3=Test Points +OutputName3=Test Point Report +OutputDocumentPath3= +OutputVariantName3= +OutputDefault3=0 +OutputType4=Plane +OutputName4=Power-Plane Prints +OutputDocumentPath4= +OutputVariantName4= +OutputDefault4=0 +PageOptions4=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType5=Mask +OutputName5=Solder/Paste Mask Prints +OutputDocumentPath5= +OutputVariantName5= +OutputDefault5=0 +PageOptions5=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType6=Drill +OutputName6=Drill Drawing/Guides +OutputDocumentPath6= +OutputVariantName6= +OutputDefault6=0 +PageOptions6=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType7=CompositeDrill +OutputName7=Composite Drill Drawing +OutputDocumentPath7= +OutputVariantName7= +OutputDefault7=0 +PageOptions7=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType8=Final +OutputName8=Final Artwork Prints +OutputDocumentPath8= +OutputVariantName8=[No Variations] +OutputDefault8=0 +PageOptions8=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType9=Gerber +OutputName9=Gerber Files +OutputDocumentPath9= +OutputVariantName9=[No Variations] +OutputDefault9=0 +Configuration9_Name1=OutputConfigurationParameter1 +Configuration9_Item1=AddToAllPlots.Set=SerializeLayerHash.Version~2,ClassName~TLayerToBoolean|CentrePlots=False|DrillDrawingSymbol=GraphicsSymbol|DrillDrawingSymbolSize=500000|EmbeddedApertures=True|FilmBorderSize=10000000|FilmXSize=200000000|FilmYSize=160000000|FlashAllFills=False|FlashPadShapes=True|G54OnApertureChange=False|GenerateDRCRulesFile=True|GenerateReliefShapes=True|GerberUnit=Imperial|IncludeUnconnectedMidLayerPads=False|LeadingAndTrailingZeroesMode=SuppressLeadingZeroes|MaxApertureSize=2500000|MinusApertureTolerance=50|Mirror.Set=SerializeLayerHash.Version~2,ClassName~TLayerToBoolean|MirrorDrillDrawingPlots=False|MirrorDrillGuidePlots=False|NumberOfDecimals=5|OptimizeChangeLocationCommands=True|OriginPosition=Relative|Panelize=False|Plot.Set=SerializeLayerHash.Version~2,ClassName~TLayerToBoolean,16973832~1,16973834~1,16777217~1,16908293~1,16908301~1,16908303~1,16973837~1,16973848~1,16973849~1|PlotPositivePlaneLayers=False|PlotUsedDrillDrawingLayerPairs=True|PlotUsedDrillGuideLayerPairs=True|PlusApertureTolerance=50|Record=GerberView|SoftwareArcs=False|Sorted=False + +[OutputGroup6] +Name=Report Outputs +Description= +TargetPrinter=Brother HL-2170W +PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1 +OutputType1=Script +OutputName1=Script Output +OutputDocumentPath1= +OutputVariantName1=[No Variations] +OutputDefault1=0 +OutputType2=ReportHierarchy +OutputName2=Report Project Hierarchy +OutputDocumentPath2= +OutputVariantName2=[No Variations] +OutputDefault2=0 +OutputType3=SinglePinNetReporter +OutputName3=Report Single Pin Nets +OutputDocumentPath3= +OutputVariantName3=[No Variations] +OutputDefault3=0 +OutputType4=SimpleBOM +OutputName4=Simple BOM +OutputDocumentPath4= +OutputVariantName4=[No Variations] +OutputDefault4=0 +OutputType5=ComponentCrossReference +OutputName5=Component Cross Reference Report +OutputDocumentPath5= +OutputVariantName5=[No Variations] +OutputDefault5=0 +OutputType6=BOM_PartType +OutputName6=Bill of Materials +OutputDocumentPath6= +OutputVariantName6=[No Variations] +OutputDefault6=0 +PageOptions6=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +Configuration6_Name1=Filter +Configuration6_Item1=545046300E5446696C74657257726170706572000D46696C7465722E416374697665090F46696C7465722E43726974657269610A04000000000000000000 +Configuration6_Name2=General +Configuration6_Item2=OpenExported=True|AddToProject=False|ForceFit=False|NotFitted=False|Database=False|IncludePCBData=False|ShowExportOptions=True|TemplateFilename=..\Altium\BOM OpenPilot.xlt|BatchMode=5|FormWidth=1226|FormHeight=598|SupplierProdQty=25|SupplierAutoQty=True|SupplierUseCachedPricing=False|SupplierCurrency= +Configuration6_Name3=GroupOrder +Configuration6_Item3=Comment=True|Footprint=True +Configuration6_Name4=OutputConfigurationParameter1 +Configuration6_Item4=Record=BOMPrintView|ShowNoERC=True|ShowParamSet=True|ShowProbe=True|ShowBlanket=True|ExpandDesignator=True|ExpandNetLabel=False|ExpandPort=False|ExpandSheetNum=False|ExpandDocNum=False +Configuration6_Name5=SortOrder +Configuration6_Item5=Designator=Up|Comment=Up|Footprint=Up +Configuration6_Name6=VisibleOrder +Configuration6_Item6=Comment=100|Description=100|Designator=100|Value=100|Footprint=100|LibRef=100|Quantity=100|Supplier 1=100|Supplier Part Number 1=100|Supplier Stock 1=100|Supplier Unit Price 1=100|Supplier Order Qty 1=100|Supplier Subtotal 1=100|Manufacturer 1=100|Manufacturer Part Number 1=100 + +[OutputGroup7] +Name=Other Outputs +Description= +TargetPrinter=Brother HL-2170W +PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1 +OutputType1=Text Print +OutputName1=Text Print +OutputDocumentPath1= +OutputVariantName1= +OutputDefault1=0 +PageOptions1=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType2=Text Print +OutputName2=Text Print +OutputDocumentPath2= +OutputVariantName2= +OutputDefault2=0 +PageOptions2=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType3=Text Print +OutputName3=Text Print +OutputDocumentPath3= +OutputVariantName3= +OutputDefault3=0 +PageOptions3=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType4=Text Print +OutputName4=Text Print +OutputDocumentPath4= +OutputVariantName4= +OutputDefault4=0 +PageOptions4=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType5=Text Print +OutputName5=Text Print +OutputDocumentPath5= +OutputVariantName5= +OutputDefault5=0 +PageOptions5=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType6=Text Print +OutputName6=Text Print +OutputDocumentPath6= +OutputVariantName6= +OutputDefault6=0 +PageOptions6=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType7=Text Print +OutputName7=Text Print +OutputDocumentPath7= +OutputVariantName7= +OutputDefault7=0 +PageOptions7=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType8=Text Print +OutputName8=Text Print +OutputDocumentPath8= +OutputVariantName8= +OutputDefault8=0 +PageOptions8=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType9=Text Print +OutputName9=Text Print +OutputDocumentPath9= +OutputVariantName9= +OutputDefault9=0 +PageOptions9=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType10=Text Print +OutputName10=Text Print +OutputDocumentPath10= +OutputVariantName10= +OutputDefault10=0 +PageOptions10=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType11=Text Print +OutputName11=Text Print +OutputDocumentPath11= +OutputVariantName11= +OutputDefault11=0 +PageOptions11=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType12=Text Print +OutputName12=Text Print +OutputDocumentPath12= +OutputVariantName12= +OutputDefault12=0 +PageOptions12=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType13=Text Print +OutputName13=Text Print +OutputDocumentPath13= +OutputVariantName13= +OutputDefault13=0 +PageOptions13=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType14=Text Print +OutputName14=Text Print +OutputDocumentPath14= +OutputVariantName14= +OutputDefault14=0 +PageOptions14=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType15=Text Print +OutputName15=Text Print +OutputDocumentPath15= +OutputVariantName15= +OutputDefault15=0 +PageOptions15=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType16=Text Print +OutputName16=Text Print +OutputDocumentPath16= +OutputVariantName16= +OutputDefault16=0 +PageOptions16=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType17=Text Print +OutputName17=Text Print +OutputDocumentPath17= +OutputVariantName17= +OutputDefault17=0 +PageOptions17=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType18=Text Print +OutputName18=Text Print +OutputDocumentPath18= +OutputVariantName18= +OutputDefault18=0 +PageOptions18=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType19=Text Print +OutputName19=Text Print +OutputDocumentPath19= +OutputVariantName19= +OutputDefault19=0 +PageOptions19=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType20=Text Print +OutputName20=Text Print +OutputDocumentPath20= +OutputVariantName20= +OutputDefault20=0 +PageOptions20=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType21=Text Print +OutputName21=Text Print +OutputDocumentPath21= +OutputVariantName21= +OutputDefault21=0 +PageOptions21=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType22=Text Print +OutputName22=Text Print +OutputDocumentPath22= +OutputVariantName22= +OutputDefault22=0 +PageOptions22=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType23=Text Print +OutputName23=Text Print +OutputDocumentPath23= +OutputVariantName23= +OutputDefault23=0 +PageOptions23=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType24=Text Print +OutputName24=Text Print +OutputDocumentPath24= +OutputVariantName24= +OutputDefault24=0 +PageOptions24=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType25=Text Print +OutputName25=Text Print +OutputDocumentPath25= +OutputVariantName25= +OutputDefault25=0 +PageOptions25=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType26=Text Print +OutputName26=Text Print +OutputDocumentPath26= +OutputVariantName26= +OutputDefault26=0 +PageOptions26=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType27=Text Print +OutputName27=Text Print +OutputDocumentPath27= +OutputVariantName27= +OutputDefault27=0 +PageOptions27=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType28=Text Print +OutputName28=Text Print +OutputDocumentPath28= +OutputVariantName28= +OutputDefault28=0 +PageOptions28=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType29=Text Print +OutputName29=Text Print +OutputDocumentPath29= +OutputVariantName29= +OutputDefault29=0 +PageOptions29=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 + +[OutputGroup8] +Name=Validation Outputs +Description= +TargetPrinter=Brother HL-2170W +PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1 +OutputType1=Electrical Rules Check +OutputName1=Electrical Rules Check +OutputDocumentPath1= +OutputVariantName1= +OutputDefault1=0 +PageOptions1=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType2=Design Rules Check +OutputName2=Design Rules Check +OutputDocumentPath2= +OutputVariantName2= +OutputDefault2=0 +PageOptions2=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType3=Differences Report +OutputName3=Differences Report +OutputDocumentPath3= +OutputVariantName3= +OutputDefault3=0 +PageOptions3=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType4=Footprint Comparison Report +OutputName4=Footprint Comparison Report +OutputDocumentPath4= +OutputVariantName4= +OutputDefault4=0 + +[OutputGroup9] +Name=Export Outputs +Description= +TargetPrinter=Brother HL-2170W +PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1 +OutputType1=ExportSTEP +OutputName1=Export STEP +OutputDocumentPath1= +OutputVariantName1= +OutputDefault1=0 + +[Modification Levels] +Type1=1 +Type2=1 +Type3=1 +Type4=1 +Type5=1 +Type6=1 +Type7=1 +Type8=1 +Type9=1 +Type10=1 +Type11=1 +Type12=1 +Type13=1 +Type14=1 +Type15=1 +Type16=1 +Type17=1 +Type18=1 +Type19=1 +Type20=1 +Type21=1 +Type22=1 +Type23=1 +Type24=1 +Type25=1 +Type26=1 +Type27=1 +Type28=1 +Type29=1 +Type30=1 +Type31=1 +Type32=1 +Type33=1 +Type34=1 +Type35=1 +Type36=1 +Type37=1 +Type38=1 +Type39=1 +Type40=1 +Type41=1 +Type42=1 +Type43=1 +Type44=1 +Type45=1 +Type46=1 +Type47=1 +Type48=1 +Type49=1 +Type50=1 +Type51=1 +Type52=1 +Type53=1 +Type54=1 +Type55=1 +Type56=1 +Type57=1 +Type58=1 +Type59=1 +Type60=1 +Type61=1 +Type62=1 +Type63=1 +Type64=1 +Type65=1 +Type66=1 +Type67=1 +Type68=1 +Type69=1 +Type70=1 +Type71=1 +Type72=1 +Type73=1 +Type74=1 + +[Difference Levels] +Type1=1 +Type2=1 +Type3=1 +Type4=1 +Type5=1 +Type6=1 +Type7=1 +Type8=1 +Type9=1 +Type10=1 +Type11=1 +Type12=1 +Type13=1 +Type14=1 +Type15=1 +Type16=1 +Type17=1 +Type18=1 +Type19=1 +Type20=1 +Type21=1 +Type22=1 +Type23=1 +Type24=1 +Type25=1 +Type26=1 +Type27=1 +Type28=1 +Type29=1 +Type30=1 +Type31=1 +Type32=1 +Type33=1 +Type34=1 +Type35=1 +Type36=1 +Type37=1 +Type38=1 +Type39=1 +Type40=1 + +[Electrical Rules Check] +Type1=1 +Type2=1 +Type3=2 +Type4=1 +Type5=2 +Type6=2 +Type7=1 +Type8=1 +Type9=1 +Type10=1 +Type11=2 +Type12=2 +Type13=2 +Type14=1 +Type15=1 +Type16=1 +Type17=1 +Type18=1 +Type19=1 +Type20=1 +Type21=1 +Type22=1 +Type23=1 +Type24=1 +Type25=2 +Type26=2 +Type27=2 +Type28=1 +Type29=1 +Type30=1 +Type31=1 +Type32=2 +Type33=2 +Type34=2 +Type35=1 +Type36=2 +Type37=1 +Type38=2 +Type39=2 +Type40=2 +Type41=0 +Type42=2 +Type43=1 +Type44=1 +Type45=2 +Type46=1 +Type47=2 +Type48=2 +Type49=1 +Type50=2 +Type51=1 +Type52=1 +Type53=1 +Type54=1 +Type55=1 +Type56=2 +Type57=1 +Type58=1 +Type59=0 +Type60=1 +Type61=2 +Type62=2 +Type63=1 +Type64=0 +Type65=2 +Type66=3 +Type67=2 +Type68=2 +Type69=1 +Type70=2 +Type71=2 +Type72=2 +Type73=2 +Type74=1 +Type75=2 +Type76=1 +Type77=1 +Type78=1 +Type79=1 +Type80=2 +Type81=3 +Type82=3 +Type83=3 +Type84=3 +Type85=3 +Type86=2 +Type87=2 +Type88=2 +Type89=1 +Type90=1 +Type91=3 +Type92=3 +Type93=2 +Type94=2 +Type95=2 +Type96=2 +Type97=2 +Type98=0 +Type99=1 +Type100=2 + +[ERC Connection Matrix] +L1=NNNNNNNNNNNWNNNWW +L2=NNWNNNNWWWNWNWNWN +L3=NWEENEEEENEWNEEWN +L4=NNENNNWEENNWNENWN +L5=NNNNNNNNNNNNNNNNN +L6=NNENNNNEENNWNENWN +L7=NNEWNNWEENNWNENWN +L8=NWEENEENEEENNEENN +L9=NWEENEEEENEWNEEWW +L10=NWNNNNNENNEWNNEWN +L11=NNENNNNEEENWNENWN +L12=WWWWNWWNWWWNWWWNN +L13=NNNNNNNNNNNWNNNWW +L14=NWEENEEEENEWNEEWW +L15=NNENNNNEEENWNENWW +L16=WWWWNWWNWWWNWWWNW +L17=WNNNNNNNWNNNWWWWN + +[Annotate] +SortOrder=3 +MatchParameter1=Comment +MatchStrictly1=1 +MatchParameter2=Library Reference +MatchStrictly2=1 +PhysicalNamingFormat=$Component_$RoomName +GlobalIndexSortOrder=3 + +[PrjClassGen] +CompClassManualEnabled=0 +CompClassManualRoomEnabled=0 +NetClassAutoBusEnabled=1 +NetClassAutoCompEnabled=0 +NetClassAutoNamedHarnessEnabled=0 +NetClassManualEnabled=1 + +[LibraryUpdateOptions] +SelectedOnly=0 +PartTypes=0 +FullReplace=1 +UpdateDesignatorLock=1 +UpdatePartIDLock=1 +PreserveParameterLocations=1 +DoGraphics=1 +DoParameters=1 +DoModels=1 +AddParameters=0 +RemoveParameters=0 +AddModels=1 +RemoveModels=1 +UpdateCurrentModels=1 + +[DatabaseUpdateOptions] +SelectedOnly=0 +PartTypes=0 + +[Comparison Options] +ComparisonOptions0=Kind=Net|MinPercent=75|MinMatch=3|ShowMatch=-1|Confirm=-1|UseName=-1|InclAllRules=0 +ComparisonOptions1=Kind=Net Class|MinPercent=75|MinMatch=3|ShowMatch=-1|Confirm=-1|UseName=-1|InclAllRules=0 +ComparisonOptions2=Kind=Component Class|MinPercent=75|MinMatch=3|ShowMatch=-1|Confirm=-1|UseName=-1|InclAllRules=0 +ComparisonOptions3=Kind=Rule|MinPercent=75|MinMatch=3|ShowMatch=-1|Confirm=-1|UseName=-1|InclAllRules=0 +ComparisonOptions4=Kind=Differential Pair|MinPercent=50|MinMatch=1|ShowMatch=0|Confirm=0|UseName=0|InclAllRules=0 +ComparisonOptions5=Kind=Structure Class|MinPercent=75|MinMatch=3|ShowMatch=-1|Confirm=-1|UseName=-1|InclAllRules=0 + +[SmartPDF] +PageOptions=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 + diff --git a/hardware/Production/Spektrum Adapter SMD/Spektrum Adapter SMD.SchDoc b/hardware/Production/Spektrum Adapter SMD/Spektrum Adapter SMD.SchDoc new file mode 100644 index 000000000..82c763fee Binary files /dev/null and b/hardware/Production/Spektrum Adapter SMD/Spektrum Adapter SMD.SchDoc differ diff --git a/make/boards/coptercontrol/board-info.mk b/make/boards/coptercontrol/board-info.mk index 547692212..1f8e52610 100644 --- a/make/boards/coptercontrol/board-info.mk +++ b/make/boards/coptercontrol/board-info.mk @@ -1,6 +1,6 @@ BOARD_TYPE := 0x04 BOARD_REVISION := 0x01 -BOOTLOADER_VERSION := 0x01 +BOOTLOADER_VERSION := 0x02 HW_TYPE := 0x01 MCU := cortex-m3 diff --git a/make/boards/openpilot/board-info.mk b/make/boards/openpilot/board-info.mk index d9cff166d..e98ac4480 100644 --- a/make/boards/openpilot/board-info.mk +++ b/make/boards/openpilot/board-info.mk @@ -1,6 +1,6 @@ BOARD_TYPE := 0x01 BOARD_REVISION := 0x01 -BOOTLOADER_VERSION := 0x00 +BOOTLOADER_VERSION := 0x01 HW_TYPE := 0x00 MCU := cortex-m3 diff --git a/make/boards/pipxtreme/board-info.mk b/make/boards/pipxtreme/board-info.mk index f9635109e..dbcb314df 100644 --- a/make/boards/pipxtreme/board-info.mk +++ b/make/boards/pipxtreme/board-info.mk @@ -1,6 +1,6 @@ BOARD_TYPE := 0x03 BOARD_REVISION := 0x01 -BOOTLOADER_VERSION := 0x00 +BOOTLOADER_VERSION := 0x01 HW_TYPE := 0x01 MCU := cortex-m3 diff --git a/make/firmware-defs.mk b/make/firmware-defs.mk index b22a66639..2eb0a13d8 100644 --- a/make/firmware-defs.mk +++ b/make/firmware-defs.mk @@ -49,6 +49,8 @@ MSG_OPFIRMWARE := ${quote} OPFW ${quote} MSG_FWINFO := ${quote} FWINFO ${quote} MSG_JTAG_PROGRAM := ${quote} JTAG-PGM ${quote} MSG_JTAG_WIPE := ${quote} JTAG-WIPE ${quote} +MSG_JTAG_RESET := ${quote} JTAG-RST ${quote} +MSG_JTAG_SAFEBOOT := ${quote} JTAG-SAFE ${quote} toprel = $(subst $(realpath $(TOP))/,,$(abspath $(1))) @@ -243,5 +245,34 @@ wipe: -c "flash erase_address pad $(2) $(3)" \ -c "reset run" \ -c "shutdown" + +reset: + @echo $(MSG_JTAG_RESET) resetting device + $(V1) $(OOCD_EXE) \ + $$(OOCD_JTAG_SETUP) \ + $$(OOCD_BOARD_RESET) \ + -c "reset run" \ + -c "shutdown" + +# Enable PWR and BKP clocks (set RCC_APB1ENR[PWREN|BKPEN]) +OOCD_WRITE_BKPDR3 = -c "mww 0x4002101C 0x18000000" +# Enable writes to BKP registers (set PWR_CR[DBP] via bit op alias address) +# +# Direct register access would be: +# mww 0x40007000 0x00000100 +# +# Direct _bit_ access is: +# Bit 8 in 0x40007000 = 0x42000000 + 0x7000 * 32 + 8 * 4 = 420E0020 +OOCD_WRITE_BKPDR3 += -c "mww 0x420E0020 0x00000001" +# Set BR3 to max value to force a safe boot +OOCD_WRITE_BKPDR3 += -c "mwh 0x40006C0C 0xFFFF" +safeboot: + @echo $(MSG_JTAG_SAFEBOOT) forcing boot into safe mode + $(V1) $(OOCD_EXE) \ + $$(OOCD_JTAG_SETUP) \ + $$(OOCD_BOARD_RESET) \ + $$(OOCD_WRITE_BKPDR3) \ + -c "reset run" \ + -c "shutdown" endef diff --git a/package/Makefile.linux b/package/Makefile.linux index c966ff6f2..78e902d71 100644 --- a/package/Makefile.linux +++ b/package/Makefile.linux @@ -2,9 +2,75 @@ # Linux-specific packaging # +define CP_DEB_FILES_TEMPLATE +.PHONY: $(2)/$(1) +$(2)/$(1): $(3)/$(1) + $(V1)cp -a $$< $$@ +endef + +# Update this number for every formal release. The Deb packaging system relies on this to know to update a +# package or not. Otherwise, the user has to uninstall first. +VERNUM := 0.1.0 +VERSION_FULL := $(VERNUM)-$(PACKAGE_LBL) + +FLIGHT_FW := coptercontrol revolution + +DEB_BUILD_DIR := $(ROOT_DIR)/debian + +SED_DATE_STRG = $(shell date -R) +SED_SCRIPT = s//$(VERSION_FULL)/;s//$(SED_DATE_STRG)/ + +DEB_CFG_CMN := $(ROOT_DIR)/package/linux/deb_common +DEB_CFG_CMN_FILES := $(shell ls $(DEB_CFG_CMN)) +DEB_CFG_I386_DIR := $(ROOT_DIR)/package/linux/deb_i386 +DEB_CFG_I386_FILES := $(shell ls $(DEB_CFG_I386_DIR)) +DEB_CFG_AMD64_DIR := $(ROOT_DIR)/package/linux/deb_amd64 +DEB_CFG_AMD64_FILES := $(shell ls $(DEB_CFG_AMD64_DIR)) +DEB_PLATFORM := amd64 +DEB_MACHINE_DIR := $(DEB_CFG_AMD64_DIR) +DEB_MACHINE_FILES := $(DEB_CFG_AMD64_FILES) +MACHINE_TYPE := $(shell uname -m) +ifneq ($(MACHINE_TYPE), x86_64) + DEB_PLATFORM := i386 + DEB_MACHINE_DIR := $(DEB_CFG_I386_DIR) + DEB_MACHINE_FILES := $(DEB_CFG_I386_FILES) +endif +ALL_DEB_FILES = $(foreach f, $(DEB_CFG_CMN_FILES), $(DEB_BUILD_DIR)/$(f)) +ALL_DEB_FILES += $(foreach f, $(DEB_MACHINE_FILES), $(DEB_BUILD_DIR)/$(f)) + +DEB_PACKAGE_NAME := openpilot_$(VERSION_FULL)_$(DEB_PLATFORM) + +linux_deb_package: deb_build gcs + @echo $@ starting + cd .. && dpkg-buildpackage -b + $(V1)mv $(ROOT_DIR)/../$(DEB_PACKAGE_NAME).deb $(BUILD_DIR) + $(V1)mv $(ROOT_DIR)/../$(DEB_PACKAGE_NAME).changes $(BUILD_DIR) + $(V1)rm -rf $(DEB_BUILD_DIR) + +deb_build: | $(DEB_BUILD_DIR) $(ALL_DEB_FILES) $(BUILD_DIR)/build + @echo $@ starting + $(V1)$(shell echo $(FW_DIR) > $(BUILD_DIR)/package_dir) + $(V1)sed -i -e "$(SED_SCRIPT)" $(DEB_BUILD_DIR)/changelog + +$(BUILD_DIR)/build: package_flight + +$(DEB_BUILD_DIR): + @echo $@ starting + $(V1)mkdir -p $(DEB_BUILD_DIR) + +$(foreach cpfile, $(DEB_CFG_CMN_FILES), $(eval $(call CP_DEB_FILES_TEMPLATE,$(cpfile),$(DEB_BUILD_DIR),$(DEB_CFG_CMN)))) + +$(foreach cpfile, $(DEB_MACHINE_FILES), $(eval $(call CP_DEB_FILES_TEMPLATE,$(cpfile),$(DEB_BUILD_DIR),$(DEB_MACHINE_DIR)))) + gcs: uavobjects + @echo "Linux Package Make of GCS." $(V1) $(MAKE) -C $(ROOT_DIR) GCS_BUILD_CONF=release $@ -ground_package: | gcs +identify: + @echo "" + @echo "We are in the Linux Package Make system." + @echo "" -.PHONY: gcs ground_package +ground_package: | identify linux_deb_package + +.PHONY: identify gcs ground_package linux_deb_package deb_build $(DEB_BUILD_DIR) diff --git a/package/linux/45-openpilot-permissions.rules b/package/linux/45-openpilot-permissions.rules new file mode 100644 index 000000000..d04d31b7f --- /dev/null +++ b/package/linux/45-openpilot-permissions.rules @@ -0,0 +1,13 @@ + # OpenPilot openpilot flight control board + SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="4117", MODE="0664", GROUP="plugdev" + SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415a", MODE="0664", GROUP="plugdev" + # OpenPilot coptercontrol flight control board + SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415b", MODE="0664", GROUP="plugdev" + # OpenPilot Pipx radio modem board + SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415c", MODE="0664", GROUP="plugdev" + # unprogrammed openpilot flight control board + SUBSYSTEM=="usb", ATTRS{idVendor}=="0483", ATTRS{idProduct}=="5750", MODE="0664", GROUP="plugdev" + # FTDI FT2232C Dual USB-UART/FIFO IC + SUBSYSTEM=="usb", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6010", MODE="0664", GROUP="plugdev" + # Olimex Ltd. OpenOCD JTAG TINY + SUBSYSTEM=="usb", ATTRS{idVendor}=="15ba", ATTRS{idProduct}=="0004", MODE="0664", GROUP="plugdev" diff --git a/package/linux/deb_amd64/control b/package/linux/deb_amd64/control new file mode 100644 index 000000000..c2408ee21 --- /dev/null +++ b/package/linux/deb_amd64/control @@ -0,0 +1,15 @@ +Source: openpilot +Section: unknown +Priority: extra +Maintainer: naiiawah +Build-Depends: debhelper (>= 7.0.50~) +Standards-Version: 3.8.4 +Homepage: http://www.openpilot.org +Vcs-Git: git://git.openpilot.org/OpenPilot.git +Vcs-Browser: http://git.openpilot.org/changelog/OpenPilot + +Package: openpilot +Architecture: amd64 +Depends: ${shlibs:Depends}, ${misc:Depends} +Description: OpenPilot GCS & FW + OpenPilot GCS and Firmware for CopterControl (CC) board. diff --git a/package/linux/deb_common/changelog b/package/linux/deb_common/changelog new file mode 100644 index 000000000..c6f9e1519 --- /dev/null +++ b/package/linux/deb_common/changelog @@ -0,0 +1,5 @@ +openpilot () unstable; urgency=low + + * Initial release (testing - unstable) + + -- naiiawah diff --git a/package/linux/deb_common/compat b/package/linux/deb_common/compat new file mode 100644 index 000000000..7f8f011eb --- /dev/null +++ b/package/linux/deb_common/compat @@ -0,0 +1 @@ +7 diff --git a/package/linux/deb_common/copyright b/package/linux/deb_common/copyright new file mode 100644 index 000000000..561d0b327 --- /dev/null +++ b/package/linux/deb_common/copyright @@ -0,0 +1,37 @@ +This work was packaged for Debian by: + + naiiawah on Thu, 27 Oct 2011 01:35:37 -0600 + +It was downloaded from: + + + +Upstream Author(s): + + + + +Copyright: + + + + +License: + + + +The Debian packaging is: + + Copyright (C) 2011 naiiawah + +# Please chose a license for your packaging work. If the program you package +# uses a mainstream license, using the same license is the safest choice. +# Please avoid to pick license terms that are more restrictive than the +# packaged work, as it may make Debian's contributions unacceptable upstream. +# If you just want it to be GPL version 3, leave the following lines in. + +and is licensed under the GPL version 3, +see "/usr/share/common-licenses/GPL-3". + +# Please also look if there are files or directories which have a +# different copyright/license attached and list them here. diff --git a/package/linux/deb_common/docs b/package/linux/deb_common/docs new file mode 100644 index 000000000..e69de29bb diff --git a/package/linux/deb_common/init.d.ex b/package/linux/deb_common/init.d.ex new file mode 100644 index 000000000..fb3e26243 --- /dev/null +++ b/package/linux/deb_common/init.d.ex @@ -0,0 +1,154 @@ +#!/bin/sh +### BEGIN INIT INFO +# Provides: openpilot +# Required-Start: $network $local_fs +# Required-Stop: +# Default-Start: 2 3 4 5 +# Default-Stop: 0 1 6 +# Short-Description: +# Description: +# <...> +# <...> +### END INIT INFO + +# Author: naiiawah + +# PATH should only include /usr/* if it runs after the mountnfs.sh script +PATH=/sbin:/usr/sbin:/bin:/usr/bin +DESC=openpilot # Introduce a short description here +NAME=openpilot # Introduce the short server's name here +DAEMON=/usr/sbin/openpilot # Introduce the server's location here +DAEMON_ARGS="" # Arguments to run the daemon with +PIDFILE=/var/run/$NAME.pid +SCRIPTNAME=/etc/init.d/$NAME + +# Exit if the package is not installed +[ -x $DAEMON ] || exit 0 + +# Read configuration variable file if it is present +[ -r /etc/default/$NAME ] && . /etc/default/$NAME + +# Load the VERBOSE setting and other rcS variables +. /lib/init/vars.sh + +# Define LSB log_* functions. +# Depend on lsb-base (>= 3.0-6) to ensure that this file is present. +. /lib/lsb/init-functions + +# +# Function that starts the daemon/service +# +do_start() +{ + # Return + # 0 if daemon has been started + # 1 if daemon was already running + # 2 if daemon could not be started + start-stop-daemon --start --quiet --pidfile $PIDFILE --exec $DAEMON --test > /dev/null \ + || return 1 + start-stop-daemon --start --quiet --pidfile $PIDFILE --exec $DAEMON -- \ + $DAEMON_ARGS \ + || return 2 + # Add code here, if necessary, that waits for the process to be ready + # to handle requests from services started subsequently which depend + # on this one. As a last resort, sleep for some time. +} + +# +# Function that stops the daemon/service +# +do_stop() +{ + # Return + # 0 if daemon has been stopped + # 1 if daemon was already stopped + # 2 if daemon could not be stopped + # other if a failure occurred + start-stop-daemon --stop --quiet --retry=TERM/30/KILL/5 --pidfile $PIDFILE --name $NAME + RETVAL="$?" + [ "$RETVAL" = 2 ] && return 2 + # Wait for children to finish too if this is a daemon that forks + # and if the daemon is only ever run from this initscript. + # If the above conditions are not satisfied then add some other code + # that waits for the process to drop all resources that could be + # needed by services started subsequently. A last resort is to + # sleep for some time. + start-stop-daemon --stop --quiet --oknodo --retry=0/30/KILL/5 --exec $DAEMON + [ "$?" = 2 ] && return 2 + # Many daemons don't delete their pidfiles when they exit. + rm -f $PIDFILE + return "$RETVAL" +} + +# +# Function that sends a SIGHUP to the daemon/service +# +do_reload() { + # + # If the daemon can reload its configuration without + # restarting (for example, when it is sent a SIGHUP), + # then implement that here. + # + start-stop-daemon --stop --signal 1 --quiet --pidfile $PIDFILE --name $NAME + return 0 +} + +case "$1" in + start) + [ "$VERBOSE" != no ] && log_daemon_msg "Starting $DESC " "$NAME" + do_start + case "$?" in + 0|1) [ "$VERBOSE" != no ] && log_end_msg 0 ;; + 2) [ "$VERBOSE" != no ] && log_end_msg 1 ;; + esac + ;; + stop) + [ "$VERBOSE" != no ] && log_daemon_msg "Stopping $DESC" "$NAME" + do_stop + case "$?" in + 0|1) [ "$VERBOSE" != no ] && log_end_msg 0 ;; + 2) [ "$VERBOSE" != no ] && log_end_msg 1 ;; + esac + ;; + status) + status_of_proc "$DAEMON" "$NAME" && exit 0 || exit $? + ;; + #reload|force-reload) + # + # If do_reload() is not implemented then leave this commented out + # and leave 'force-reload' as an alias for 'restart'. + # + #log_daemon_msg "Reloading $DESC" "$NAME" + #do_reload + #log_end_msg $? + #;; + restart|force-reload) + # + # If the "reload" option is implemented then remove the + # 'force-reload' alias + # + log_daemon_msg "Restarting $DESC" "$NAME" + do_stop + case "$?" in + 0|1) + do_start + case "$?" in + 0) log_end_msg 0 ;; + 1) log_end_msg 1 ;; # Old process is still running + *) log_end_msg 1 ;; # Failed to start + esac + ;; + *) + # Failed to stop + log_end_msg 1 + ;; + esac + ;; + *) + #echo "Usage: $SCRIPTNAME {start|stop|restart|reload|force-reload}" >&2 + echo "Usage: $SCRIPTNAME {start|stop|status|restart|force-reload}" >&2 + exit 3 + ;; +esac + +: diff --git a/package/linux/deb_common/manpage.1.ex b/package/linux/deb_common/manpage.1.ex new file mode 100644 index 000000000..1d0199483 --- /dev/null +++ b/package/linux/deb_common/manpage.1.ex @@ -0,0 +1,59 @@ +.\" Hey, EMACS: -*- nroff -*- +.\" First parameter, NAME, should be all caps +.\" Second parameter, SECTION, should be 1-8, maybe w/ subsection +.\" other parameters are allowed: see man(7), man(1) +.TH OPENPILOT SECTION "October 27, 2011" +.\" Please adjust this date whenever revising the manpage. +.\" +.\" Some roff macros, for reference: +.\" .nh disable hyphenation +.\" .hy enable hyphenation +.\" .ad l left justify +.\" .ad b justify to both left and right margins +.\" .nf disable filling +.\" .fi enable filling +.\" .br insert line break +.\" .sp insert n+1 empty lines +.\" for manpage-specific macros, see man(7) +.SH NAME +openpilot \- program to do something +.SH SYNOPSIS +.B openpilot +.RI [ options ] " files" ... +.br +.B bar +.RI [ options ] " files" ... +.SH DESCRIPTION +This manual page documents briefly the +.B openpilot +and +.B bar +commands. +.PP +.\" TeX users may be more comfortable with the \fB\fP and +.\" \fI\fP escape sequences to invode bold face and italics, +.\" respectively. +\fBopenpilot\fP is a program that... +.SH OPTIONS +These programs follow the usual GNU command line syntax, with long +options starting with two dashes (`-'). +A summary of options is included below. +For a complete description, see the Info files. +.TP +.B \-h, \-\-help +Show summary of options. +.TP +.B \-v, \-\-version +Show version of program. +.SH SEE ALSO +.BR bar (1), +.BR baz (1). +.br +The programs are documented fully by +.IR "The Rise and Fall of a Fooish Bar" , +available via the Info system. +.SH AUTHOR +openpilot was written by . +.PP +This manual page was written by naiiawah , +for the Debian project (and may be used by others). diff --git a/package/linux/deb_common/manpage.sgml.ex b/package/linux/deb_common/manpage.sgml.ex new file mode 100644 index 000000000..76b474e3e --- /dev/null +++ b/package/linux/deb_common/manpage.sgml.ex @@ -0,0 +1,154 @@ + manpage.1'. You may view + the manual page with: `docbook-to-man manpage.sgml | nroff -man | + less'. A typical entry in a Makefile or Makefile.am is: + +manpage.1: manpage.sgml + docbook-to-man $< > $@ + + + The docbook-to-man binary is found in the docbook-to-man package. + Please remember that if you create the nroff version in one of the + debian/rules file targets (such as build), you will need to include + docbook-to-man in your Build-Depends control field. + + --> + + + FIRSTNAME"> + SURNAME"> + + October 27, 2011"> + + SECTION"> + naiiawah@none"> + + OPENPILOT"> + + + Debian"> + GNU"> + GPL"> +]> + + + +
+ &dhemail; +
+ + &dhfirstname; + &dhsurname; + + + 2003 + &dhusername; + + &dhdate; +
+ + &dhucpackage; + + &dhsection; + + + &dhpackage; + + program to do something + + + + &dhpackage; + + + + + + + + DESCRIPTION + + This manual page documents briefly the + &dhpackage; and bar + commands. + + This manual page was written for the &debian; distribution + because the original program does not have a manual page. + Instead, it has documentation in the &gnu; + Info format; see below. + + &dhpackage; is a program that... + + + + OPTIONS + + These programs follow the usual &gnu; command line syntax, + with long options starting with two dashes (`-'). A summary of + options is included below. For a complete description, see the + Info files. + + + + + + + + Show summary of options. + + + + + + + + Show version of program. + + + + + + SEE ALSO + + bar (1), baz (1). + + The programs are documented fully by The Rise and + Fall of a Fooish Bar available via the + Info system. + + + AUTHOR + + This manual page was written by &dhusername; &dhemail; for + the &debian; system (and may be used by others). Permission is + granted to copy, distribute and/or modify this document under + the terms of the &gnu; General Public License, Version 2 any + later version published by the Free Software Foundation. + + + On Debian systems, the complete text of the GNU General Public + License can be found in /usr/share/common-licenses/GPL. + + + +
+ + diff --git a/package/linux/deb_common/manpage.xml.ex b/package/linux/deb_common/manpage.xml.ex new file mode 100644 index 000000000..b8c0d8411 --- /dev/null +++ b/package/linux/deb_common/manpage.xml.ex @@ -0,0 +1,291 @@ + +.
will be generated. You may view the +manual page with: nroff -man .
| less'. A typical entry +in a Makefile or Makefile.am is: + +DB2MAN = /usr/share/sgml/docbook/stylesheet/xsl/docbook-xsl/manpages/docbook.xsl +XP = xsltproc -''-nonet -''-param man.charmap.use.subset "0" + +manpage.1: manpage.xml + $(XP) $(DB2MAN) $< + +The xsltproc binary is found in the xsltproc package. The XSL files are in +docbook-xsl. A description of the parameters you can use can be found in the +docbook-xsl-doc-* packages. Please remember that if you create the nroff +version in one of the debian/rules file targets (such as build), you will need +to include xsltproc and docbook-xsl in your Build-Depends control field. +Alternatively use the xmlto command/package. That will also automatically +pull in xsltproc and docbook-xsl. + +Notes for using docbook2x: docbook2x-man does not automatically create the +AUTHOR(S) and COPYRIGHT sections. In this case, please add them manually as + ... . + +To disable the automatic creation of the AUTHOR(S) and COPYRIGHT sections +read /usr/share/doc/docbook-xsl/doc/manpages/authors.html. This file can be +found in the docbook-xsl-doc-html package. + +Validation can be done using: `xmllint -''-noout -''-valid manpage.xml` + +General documentation about man-pages and man-page-formatting: +man(1), man(7), http://www.tldp.org/HOWTO/Man-Page/ + +--> + + + + + + + + + + + + + +]> + + + + &dhtitle; + &dhpackage; + + + &dhfirstname; + &dhsurname; + Wrote this manpage for the Debian system. +
+ &dhemail; +
+
+
+ + 2007 + &dhusername; + + + This manual page was written for the Debian system + (and may be used by others). + Permission is granted to copy, distribute and/or modify this + document under the terms of the GNU General Public License, + Version 2 or (at your option) any later version published by + the Free Software Foundation. + On Debian systems, the complete text of the GNU General Public + License can be found in + /usr/share/common-licenses/GPL. + +
+ + &dhucpackage; + &dhsection; + + + &dhpackage; + program to do something + + + + &dhpackage; + + + + + + + + + this + + + + + + + + this + that + + + + + &dhpackage; + + + + + + + + + + + + + + + + + + + DESCRIPTION + This manual page documents briefly the + &dhpackage; and bar + commands. + This manual page was written for the Debian distribution + because the original program does not have a manual page. + Instead, it has documentation in the GNU + info + 1 + format; see below. + &dhpackage; is a program that... + + + OPTIONS + The program follows the usual GNU command line syntax, + with long options starting with two dashes (`-'). A summary of + options is included below. For a complete description, see the + + info + 1 + files. + + + + + + + Does this and that. + + + + + + + Show summary of options. + + + + + + + Show version of program. + + + + + + FILES + + + /etc/foo.conf + + The system-wide configuration file to control the + behaviour of &dhpackage;. See + + foo.conf + 5 + for further details. + + + + ${HOME}/.foo.conf + + The per-user configuration file to control the + behaviour of &dhpackage;. See + + foo.conf + 5 + for further details. + + + + + + ENVIONMENT + + + FOO_CONF + + If used, the defined file is used as configuration + file (see also ). + + + + + + DIAGNOSTICS + The following diagnostics may be issued + on stderr: + + + Bad configuration file. Exiting. + + The configuration file seems to contain a broken configuration + line. Use the option, to get more info. + + + + + &dhpackage; provides some return codes, that can + be used in scripts: + + Code + Diagnostic + + 0 + Program exited successfully. + + + 1 + The configuration file seems to be broken. + + + + + + BUGS + The program is currently limited to only work + with the foobar library. + The upstreams BTS can be found + at . + + + SEE ALSO + + + bar + 1 + , + baz + 1 + , + foo.conf + 5 + + The programs are documented fully by The Rise and + Fall of a Fooish Bar available via the + info + 1 + system. + +
+ diff --git a/package/linux/deb_common/menu.ex b/package/linux/deb_common/menu.ex new file mode 100644 index 000000000..c5a80a7bc --- /dev/null +++ b/package/linux/deb_common/menu.ex @@ -0,0 +1,2 @@ +?package(openpilot):needs="X11|text|vc|wm" section="Applications/see-menu-manual"\ + title="openpilot" command="/usr/bin/openpilot" diff --git a/package/linux/deb_common/openpilot.cron.d.ex b/package/linux/deb_common/openpilot.cron.d.ex new file mode 100644 index 000000000..bc3507489 --- /dev/null +++ b/package/linux/deb_common/openpilot.cron.d.ex @@ -0,0 +1,4 @@ +# +# Regular cron jobs for the openpilot package +# +0 4 * * * root [ -x /usr/bin/openpilot_maintenance ] && /usr/bin/openpilot_maintenance diff --git a/package/linux/deb_common/openpilot.debhelper.log b/package/linux/deb_common/openpilot.debhelper.log new file mode 100644 index 000000000..34de80b19 --- /dev/null +++ b/package/linux/deb_common/openpilot.debhelper.log @@ -0,0 +1,15 @@ +dh_prep +dh_installdirs +dh_installchangelogs +dh_installdocs +dh_installexamples +dh_installman +dh_link +dh_strip +dh_compress +dh_fixperms +dh_installdeb +dh_shlibdeps +dh_gencontrol +dh_md5sums +dh_builddeb diff --git a/package/linux/deb_common/openpilot.default.ex b/package/linux/deb_common/openpilot.default.ex new file mode 100644 index 000000000..0b172a1fc --- /dev/null +++ b/package/linux/deb_common/openpilot.default.ex @@ -0,0 +1,10 @@ +# Defaults for openpilot initscript +# sourced by /etc/init.d/openpilot +# installed at /etc/default/openpilot by the maintainer scripts + +# +# This is a POSIX shell fragment +# + +# Additional options that are passed to the Daemon. +DAEMON_OPTS="" diff --git a/package/linux/deb_common/openpilot.dirs b/package/linux/deb_common/openpilot.dirs new file mode 100644 index 000000000..08bf6a7e1 --- /dev/null +++ b/package/linux/deb_common/openpilot.dirs @@ -0,0 +1,6 @@ +etc/xdg/menus/applications-merged +usr/share/applications +usr/share/pixmaps +usr/share/desktop-directories +usr/local/OpenPilot/firmware +usr/bin diff --git a/package/linux/deb_common/openpilot.doc-base.EX b/package/linux/deb_common/openpilot.doc-base.EX new file mode 100644 index 000000000..9e24da0dc --- /dev/null +++ b/package/linux/deb_common/openpilot.doc-base.EX @@ -0,0 +1,20 @@ +Document: openpilot +Title: Debian openpilot Manual +Author: +Abstract: This manual describes what openpilot is + and how it can be used to + manage online manuals on Debian systems. +Section: unknown + +Format: debiandoc-sgml +Files: /usr/share/doc/openpilot/openpilot.sgml.gz + +Format: postscript +Files: /usr/share/doc/openpilot/openpilot.ps.gz + +Format: text +Files: /usr/share/doc/openpilot/openpilot.text.gz + +Format: HTML +Index: /usr/share/doc/openpilot/html/index.html +Files: /usr/share/doc/openpilot/html/*.html diff --git a/package/linux/deb_common/openpilot.substvars b/package/linux/deb_common/openpilot.substvars new file mode 100644 index 000000000..39006599c --- /dev/null +++ b/package/linux/deb_common/openpilot.substvars @@ -0,0 +1,2 @@ +shlibs:Depends=libc6 (>= 2.3.6-6~), libc6 (>= 2.4), libgcc1 (>= 1:4.1.1), libgl1-mesa-glx | libgl1, libglu1-mesa | libglu1, libphonon4 (>= 4:4.3.0), libqt4-network (>= 4:4.6.1), libqt4-opengl (>= 4:4.6.1), libqt4-script (>= 4:4.5.3), libqt4-sql (>= 4:4.5.3), libqt4-svg (>= 4:4.5.3), libqt4-test (>= 4:4.5.3), libqt4-xml (>= 4:4.5.3), libqtcore4 (>= 4:4.7.0~beta1), libqtgui4 (>= 4:4.6.2), libsdl1.2debian (>= 1.2.10-1), libstdc++6 (>= 4.1.1), libudev0 (>= 147), libusb-0.1-4 (>= 2:0.1.12), phonon +misc:Depends= diff --git a/package/linux/deb_common/openpilot.udev b/package/linux/deb_common/openpilot.udev new file mode 100644 index 000000000..3d84dd426 --- /dev/null +++ b/package/linux/deb_common/openpilot.udev @@ -0,0 +1,18 @@ + # OpenPilot Flight Control board + SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="4117", MODE="0664", GROUP="plugdev" + # OpenPilot OP board + SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415a", MODE="0664", GROUP="plugdev" + # OpenPilot CopterControl flight control board + SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415b", MODE="0664", GROUP="plugdev" + # OpenPilot Pipx radio modem board + SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415c", MODE="0664", GROUP="plugdev" + # OpenPilot CopterControl3D flight control board + SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415d", MODE="0664", GROUP="plugdev" + # OpenPilot Revolution flight control board + SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415e", MODE="0664", GROUP="plugdev" + # unprogrammed openpilot flight control board + SUBSYSTEM=="usb", ATTRS{idVendor}=="0483", ATTRS{idProduct}=="5750", MODE="0664", GROUP="plugdev" + # FTDI FT2232C Dual USB-UART/FIFO IC + SUBSYSTEM=="usb", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6010", MODE="0664", GROUP="plugdev" + # Olimex Ltd. OpenOCD JTAG TINY + SUBSYSTEM=="usb", ATTRS{idVendor}=="15ba", ATTRS{idProduct}=="0004", MODE="0664", GROUP="plugdev" diff --git a/package/linux/deb_common/postinst b/package/linux/deb_common/postinst new file mode 100644 index 000000000..df8022075 --- /dev/null +++ b/package/linux/deb_common/postinst @@ -0,0 +1,40 @@ +#!/bin/sh +# postinst script for openpilot +# +# see: dh_installdeb(1) + +set -e + +# summary of how this script can be called: +# * `configure' +# * `abort-upgrade' +# * `abort-remove' `in-favour' +# +# * `abort-remove' +# * `abort-deconfigure' `in-favour' +# `removing' +# +# for details, see http://www.debian.org/doc/debian-policy/ or +# the debian-policy package + + +case "$1" in + configure) + sudo udevadm control --reload-rules >&2 + ;; + + abort-upgrade|abort-remove|abort-deconfigure) + ;; + + *) + echo "postinst called with unknown argument \`$1'" >&2 + exit 1 + ;; +esac + +# dh_installdeb will replace this with shell code automatically +# generated by other debhelper scripts. + +#DEBHELPER# + +exit 0 diff --git a/package/linux/deb_common/postinst.ex b/package/linux/deb_common/postinst.ex new file mode 100644 index 000000000..e8295471c --- /dev/null +++ b/package/linux/deb_common/postinst.ex @@ -0,0 +1,39 @@ +#!/bin/sh +# postinst script for openpilot +# +# see: dh_installdeb(1) + +set -e + +# summary of how this script can be called: +# * `configure' +# * `abort-upgrade' +# * `abort-remove' `in-favour' +# +# * `abort-remove' +# * `abort-deconfigure' `in-favour' +# `removing' +# +# for details, see http://www.debian.org/doc/debian-policy/ or +# the debian-policy package + + +case "$1" in + configure) + ;; + + abort-upgrade|abort-remove|abort-deconfigure) + ;; + + *) + echo "postinst called with unknown argument \`$1'" >&2 + exit 1 + ;; +esac + +# dh_installdeb will replace this with shell code automatically +# generated by other debhelper scripts. + +#DEBHELPER# + +exit 0 diff --git a/package/linux/deb_common/postrm.ex b/package/linux/deb_common/postrm.ex new file mode 100644 index 000000000..7494eff83 --- /dev/null +++ b/package/linux/deb_common/postrm.ex @@ -0,0 +1,37 @@ +#!/bin/sh +# postrm script for openpilot +# +# see: dh_installdeb(1) + +set -e + +# summary of how this script can be called: +# * `remove' +# * `purge' +# * `upgrade' +# * `failed-upgrade' +# * `abort-install' +# * `abort-install' +# * `abort-upgrade' +# * `disappear' +# +# for details, see http://www.debian.org/doc/debian-policy/ or +# the debian-policy package + + +case "$1" in + purge|remove|upgrade|failed-upgrade|abort-install|abort-upgrade|disappear) + ;; + + *) + echo "postrm called with unknown argument \`$1'" >&2 + exit 1 + ;; +esac + +# dh_installdeb will replace this with shell code automatically +# generated by other debhelper scripts. + +#DEBHELPER# + +exit 0 diff --git a/package/linux/deb_common/preinst.ex b/package/linux/deb_common/preinst.ex new file mode 100644 index 000000000..32ac40cc3 --- /dev/null +++ b/package/linux/deb_common/preinst.ex @@ -0,0 +1,35 @@ +#!/bin/sh +# preinst script for openpilot +# +# see: dh_installdeb(1) + +set -e + +# summary of how this script can be called: +# * `install' +# * `install' +# * `upgrade' +# * `abort-upgrade' +# for details, see http://www.debian.org/doc/debian-policy/ or +# the debian-policy package + + +case "$1" in + install|upgrade) + ;; + + abort-upgrade) + ;; + + *) + echo "preinst called with unknown argument \`$1'" >&2 + exit 1 + ;; +esac + +# dh_installdeb will replace this with shell code automatically +# generated by other debhelper scripts. + +#DEBHELPER# + +exit 0 diff --git a/package/linux/deb_common/prerm.ex b/package/linux/deb_common/prerm.ex new file mode 100644 index 000000000..a46c87175 --- /dev/null +++ b/package/linux/deb_common/prerm.ex @@ -0,0 +1,38 @@ +#!/bin/sh +# prerm script for openpilot +# +# see: dh_installdeb(1) + +set -e + +# summary of how this script can be called: +# * `remove' +# * `upgrade' +# * `failed-upgrade' +# * `remove' `in-favour' +# * `deconfigure' `in-favour' +# `removing' +# +# for details, see http://www.debian.org/doc/debian-policy/ or +# the debian-policy package + + +case "$1" in + remove|upgrade|deconfigure) + ;; + + failed-upgrade) + ;; + + *) + echo "prerm called with unknown argument \`$1'" >&2 + exit 1 + ;; +esac + +# dh_installdeb will replace this with shell code automatically +# generated by other debhelper scripts. + +#DEBHELPER# + +exit 0 diff --git a/package/linux/deb_common/rules b/package/linux/deb_common/rules new file mode 100644 index 000000000..ba22c1e9c --- /dev/null +++ b/package/linux/deb_common/rules @@ -0,0 +1,85 @@ +#!/usr/bin/make -f +# -*- makefile -*- +# Sample debian/rules that uses debhelper. +# +# This file was originally written by Joey Hess and Craig Small. +# As a special exception, when this file is copied by dh-make into a +# dh-make output file, you may use that output file without restriction. +# This special exception was added by Craig Small in version 0.37 of dh-make. +# +# Modified to make a template file for a multi-binary package with separated +# build-arch and build-indep targets by Bill Allombert 2001 + +# Uncomment this to turn on verbose mode. +# export DH_VERBOSE=1 + +# This has to be exported to make some magic below work. +export DH_OPTIONS=-v + +#%: +# dh $@ + +PACKAGE_DIR = $(shell cat build/package_dir) + +clean: + dh_testdir + dh_testroot + dh_clean + +install: + dh_testdir + dh_testroot + dh_prep + dh_installdirs + dh_installudev --priority=45 + # Add here commands to install the package into debian/ + cp -arp build/ground/openpilotgcs/bin debian/openpilot/usr/local/OpenPilot + cp -arp build/ground/openpilotgcs/lib debian/openpilot/usr/local/OpenPilot + cp -arp build/ground/openpilotgcs/share debian/openpilot/usr/local/OpenPilot + cp -arp build/ground/openpilotgcs/.obj debian/openpilot/usr/local/OpenPilot + cp -arp build/ground/openpilotgcs/gcsversioninfo.h debian/openpilot/usr/local/OpenPilot + cp -arp package/linux/openpilot.desktop debian/openpilot/usr/share/applications + cp -arp package/linux/openpilot.png debian/openpilot/usr/share/pixmaps + cp -arp package/linux/openpilot_menu.png debian/openpilot/usr/share/pixmaps + cp -arp package/linux/openpilot_menu.menu debian/openpilot/etc/xdg/menus/applications-merged + cp -arp package/linux/openpilot_menu.directory debian/openpilot/usr/share/desktop-directories +ifdef PACKAGE_DIR + cp -a $(PACKAGE_DIR)/*.opfw debian/openpilot/usr/local/OpenPilot/firmware/ +else + $(error PACKAGE_DIR not defined! $(PACKAGE_DIR)) +endif + ln -s /usr/local/OpenPilot/bin/openpilotgcs.bin `pwd`/debian/openpilot/usr/bin/openpilot-gcs + rm -rf debian/openpilot/usr/local/OpenPilot/share/openpilotgcs/sounds/sounds + rm -rf debian/openpilot/usr/local/OpenPilot/share/openpilotgcs/pfd/pfd + rm -rf debian/openpilot/usr/local/OpenPilot/share/openpilotgcs/models/models + rm -rf debian/openpilot/usr/local/OpenPilot/share/openpilotgcs/mapicons/mapicons + rm -rf debian/openpilot/usr/local/OpenPilot/share/openpilotgcs/dials/dials + rm -rf debian/openpilot/usr/local/OpenPilot/share/openpilotgcs/diagrams/diagrams + + +# Build architecture-independent files here. +binary-indep: install + +# We have nothing to build by default. Got taken care of by OPs build system +# Build architecture-dependent files here. +binary-arch: install + dh_testdir + dh_testroot + dh_installchangelogs + dh_installdocs + dh_installexamples + dh_installman + dh_link + dh_strip + dh_compress + dh_fixperms + dh_installdeb + dh_shlibdeps -l/usr/local/OpenPilot/lib/openpilotgcs --dpkg-shlibdeps-params="--ignore-missing-info -v" + dh_gencontrol + dh_md5sums + dh_builddeb + +binary: binary-indep binary-arch + +.PHONY: clean binary-indep binary-arch binary install + diff --git a/package/linux/deb_common/watch.ex b/package/linux/deb_common/watch.ex new file mode 100644 index 000000000..7e9872e99 --- /dev/null +++ b/package/linux/deb_common/watch.ex @@ -0,0 +1,23 @@ +# Example watch control file for uscan +# Rename this file to "watch" and then you can run the "uscan" command +# to check for upstream updates and more. +# See uscan(1) for format + +# Compulsory line, this is a version 3 file +version=3 + +# Uncomment to examine a Webpage +# +#http://www.example.com/downloads.php openpilot-(.*)\.tar\.gz + +# Uncomment to examine a Webserver directory +#http://www.example.com/pub/openpilot-(.*)\.tar\.gz + +# Uncommment to examine a FTP server +#ftp://ftp.example.com/pub/openpilot-(.*)\.tar\.gz debian uupdate + +# Uncomment to find new files on sourceforge, for devscripts >= 2.9 +# http://sf.net/openpilot/openpilot-(.*)\.tar\.gz + +# Uncomment to find new files on GooglePages +# http://example.googlepages.com/foo.html openpilot-(.*)\.tar\.gz diff --git a/package/linux/deb_i386/control b/package/linux/deb_i386/control new file mode 100644 index 000000000..e93d4f559 --- /dev/null +++ b/package/linux/deb_i386/control @@ -0,0 +1,15 @@ +Source: openpilot +Section: unknown +Priority: extra +Maintainer: naiiawah +Build-Depends: debhelper (>= 7.0.50~) +Standards-Version: 3.8.4 +Homepage: http://www.openpilot.org +Vcs-Git: git://git.openpilot.org/OpenPilot.git +Vcs-Browser: http://git.openpilot.org/changelog/OpenPilot + +Package: openpilot +Architecture: i386 +Depends: ${shlibs:Depends}, ${misc:Depends} +Description: OpenPilot GCS & FW + OpenPilot GCS and Firmware for CopterControl (CC) board. diff --git a/package/linux/openpilot.desktop b/package/linux/openpilot.desktop new file mode 100644 index 000000000..5ce67af5d --- /dev/null +++ b/package/linux/openpilot.desktop @@ -0,0 +1,12 @@ +[Desktop Entry] +Version=0.1.0 +Encoding=UTF-8 +Name=OpenPilot GCS +Exec=openpilot-gcs +TryExec=openpilot-gcs +Comment=Configure, Tune, Diagnose, Track, & Upgrade FW for OpenPilot solutions +Terminal=false +Categories=OpenPilotMenu;Qt;Other; +Icon=openpilot +Type=Application +MimeType=application/openpilot.snapshot; diff --git a/package/linux/openpilot.png b/package/linux/openpilot.png new file mode 100755 index 000000000..e9c4ee868 Binary files /dev/null and b/package/linux/openpilot.png differ diff --git a/package/linux/openpilot_menu.directory b/package/linux/openpilot_menu.directory new file mode 100644 index 000000000..7175a8915 --- /dev/null +++ b/package/linux/openpilot_menu.directory @@ -0,0 +1,5 @@ +[Desktop Entry] +Type=Directory +Encoding=UTF-8 +Name=OpenPilot +Icon=openpilot_menu.png diff --git a/package/linux/openpilot_menu.menu b/package/linux/openpilot_menu.menu new file mode 100644 index 000000000..9e35577ec --- /dev/null +++ b/package/linux/openpilot_menu.menu @@ -0,0 +1,12 @@ + + + Applications + + OpenPilot + openpilot_menu.directory + + OpenPilotMenu + + + diff --git a/package/linux/openpilot_menu.png b/package/linux/openpilot_menu.png new file mode 100755 index 000000000..b5e10befa Binary files /dev/null and b/package/linux/openpilot_menu.png differ diff --git a/shared/uavobjectdefinition/attitudesettings.xml b/shared/uavobjectdefinition/attitudesettings.xml index 677493d68..e60c2454b 100644 --- a/shared/uavobjectdefinition/attitudesettings.xml +++ b/shared/uavobjectdefinition/attitudesettings.xml @@ -10,6 +10,7 @@ + diff --git a/shared/uavobjectdefinition/camerastabsettings.xml b/shared/uavobjectdefinition/camerastabsettings.xml index 09199b77a..069abdeb3 100644 --- a/shared/uavobjectdefinition/camerastabsettings.xml +++ b/shared/uavobjectdefinition/camerastabsettings.xml @@ -1,8 +1,12 @@ Settings for the @ref CameraStab mmodule - + + + + + diff --git a/shared/uavobjectdefinition/faultsettings.xml b/shared/uavobjectdefinition/faultsettings.xml new file mode 100644 index 000000000..8d02f0d78 --- /dev/null +++ b/shared/uavobjectdefinition/faultsettings.xml @@ -0,0 +1,12 @@ + + + Allows testers to simulate various fault scenarios. + + + + + + + + + diff --git a/shared/uavobjectdefinition/hwsettings.xml b/shared/uavobjectdefinition/hwsettings.xml index 9ec859fa3..455e23cd7 100644 --- a/shared/uavobjectdefinition/hwsettings.xml +++ b/shared/uavobjectdefinition/hwsettings.xml @@ -2,8 +2,8 @@ Selection of optional hardware configurations. - - + + @@ -11,8 +11,12 @@ + + + + - + diff --git a/shared/uavobjectdefinition/systemalarms.xml b/shared/uavobjectdefinition/systemalarms.xml index c95963f88..cc20045b6 100644 --- a/shared/uavobjectdefinition/systemalarms.xml +++ b/shared/uavobjectdefinition/systemalarms.xml @@ -2,7 +2,7 @@ Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules. + elementnames="OutOfMemory,StackOverflow,CPUOverload,EventSystem,SDCard,Telemetry,ManualControl,Actuator,Attitude,Sensors,Stabilization,Guidance,AHRSComms,Battery,FlightTime,I2C,GPS,BootFault" defaultvalue="Uninitialised"/> diff --git a/shared/uavobjectdefinition/taskinfo.xml b/shared/uavobjectdefinition/taskinfo.xml index 532ca76a2..02ee82037 100644 --- a/shared/uavobjectdefinition/taskinfo.xml +++ b/shared/uavobjectdefinition/taskinfo.xml @@ -1,9 +1,9 @@ Task information - - - + + +