From 5c0c3a0f08480f361ec8991b706b8c08074f9853 Mon Sep 17 00:00:00 2001 From: night-ghost Date: Mon, 5 Mar 2018 10:27:19 +0500 Subject: [PATCH] AP_HAL_F4Light: parameters divided into common and board-specific, added new parameter to reboot into DFU mode --- .../boards/f4light_Airbot/board.h | 131 +---------------- .../f4light_Airbot/support/UPLOAD-STLINK.sh | 4 +- .../boards/f4light_AirbotV2/board.cpp | 8 +- .../boards/f4light_AirbotV2/board.h | 117 +-------------- .../boards/f4light_MatekF405_OSD/board.h | 114 +-------------- .../boards/f4light_MiniF4_OSD/board.h | 97 +------------ .../boards/f4light_Revolution/board.h | 133 +----------------- .../boards/f4light_cl_racing/board.h | 122 +--------------- libraries/AP_HAL_F4Light/params.h | 113 +++++++++++++++ 9 files changed, 137 insertions(+), 702 deletions(-) create mode 100644 libraries/AP_HAL_F4Light/params.h diff --git a/libraries/AP_HAL_F4Light/boards/f4light_Airbot/board.h b/libraries/AP_HAL_F4Light/boards/f4light_Airbot/board.h index f70533817d..19d13e5b12 100644 --- a/libraries/AP_HAL_F4Light/boards/f4light_Airbot/board.h +++ b/libraries/AP_HAL_F4Light/boards/f4light_Airbot/board.h @@ -130,7 +130,7 @@ #define BOARD_DATAFLASH_NAME "dataflash" -#define BOARD_DATAFLASH_PAGES 0x2000 +#define BOARD_DATAFLASH_PAGES 0x10000 #define BOARD_DATAFLASH_ERASE_SIZE (4096)// in bytes #if 1// if board's dataflash supports 4k erases then we can use it as FAT and share it via USB @@ -178,148 +178,27 @@ /* - // @Param: MOTOR_LAYOUT - // @DisplayName: Motor layout scheme - // @Description: Selects how motors are numbered - // @Values: 0:ArduCopter, 1: Ardupilot with pins 2&3 for servos 2:OpenPilot,3:CleanFlight - // @User: Advanced - AP_GROUPINFO("_MOTOR_LAYOUT", 0, HAL_F4Light, _motor_layout, 0), - - // @Param: USE_SOFTSERIAL - // @DisplayName: Use SoftwareSerial driver - // @Description: Use SoftwareSerial driver instead SoftwareI2C on Input Port pins 7 & 8 - // @Values: 0:disabled,1:enabled - // @User: Advanced - AP_GROUPINFO("_USE_SOFTSERIAL", 1, HAL_F4Light, _use_softserial, 0), - - // @Param: UART_SBUS - // @DisplayName: What UART to use as SBUS input - // @Description: Allows to use any UART as SBUS input - // @Values: 0:disabled,1:UART1, 2:UART2 etc - // @User: Advanced - AP_GROUPINFO("UART_SBUS", 3, AP_Param_Helper, _uart_sbus, 0), \ - - // @Param: SERVO_MASK - // @DisplayName: Servo Mask of Input port - // @Description: Enable selected pins of Input port to be used as Servo Out - // @Values: 0:disabled,1:enable pin3 (PPM_1), 2: enable pin4 (PPM_2), 4: enable pin5 (UART6_TX) , 8: enable pin6 (UART6_RX), 16: enable pin7, 32: enable pin8 - // @User: Advanced - AP_GROUPINFO("SERVO_MASK", 2, AP_Param_Helper, _servo_mask, 0) \ - - // @Param: CONNECT_COM - // @DisplayName: connect to COM port - // @Description: Allows to connect USB to arbitrary UART, thus allowing to configure devices on that UARTs. Auto-reset. - // @Values: 0:disabled, 1:connect to port 1, 2:connect to port 2, etc - // @User: Advanced - AP_GROUPINFO("CONNECT_COM", 2, AP_Param_Helper, _connect_com, 0) \ - - // @Param: CONNECT_ESC - // @DisplayName: connect to ESC inputs via 4wayIf - // @Description: Allows to connect USB to ESC inputs, thus allowing to configure ESC as on 4-wayIf. Auto-reset. - // @Values: 0:disabled, 1:connect uartA to ESC, 2: connect uartB to ESC, etc - // @User: Advanced - AP_GROUPINFO("CONNECT_ESC", 2, AP_Param_Helper, _connect_esc, 0) \ - - // @Param: FLEXI_I2C - // @DisplayName: use FlexiPort as I2C, not USART - // @Description: Allows to switch FlexiPort usage between USART and I2C modes - // @Values: 0:USART, 1:I2C - // @User: Advanced - AP_GROUPINFO("FLEXI_I2C", 6, AP_Param_Helper, _flexi_i2c, 0) \ - - // @Param: PWM_TYPE - // @DisplayName: PWM protocol used - // @Description: Allows to ignore MOT_PWM_TYPE param and set PWM protocol independently - // @Values: 0:use MOT_PWM_TYPE, 1:OneShot 2:OneShot125 3:OneShot42 4:PWM125 - // @User: Advanced - AP_GROUPINFO("PWM_TYPE", 7, AP_Param_Helper, _pwm_type, 0) - - // @Param: RC_INPUT - // @DisplayName: Type of RC input - // @Description: allows to force specified RC input port - // @Values: 0:auto, 1:PPM1 (pin3), 2: PPM2 (pin4) etc - // @User: Advanced - AP_GROUPINFO("RC_INPUT", 9, AP_Param_Helper, _rc_input, 0) - - // @Param: AIBAO_FS - // @DisplayName: Support FailSafe for Walkera Aibao RC - // @Description: Allows to translate of Walkera Aibao RC FailSafe to Ardupilot's failsafe - // @Values: 0: not translate, 1:translate - // @User: Advanced - AP_GROUPINFO("AIBAO_FS", 7, AP_Param_Helper, _aibao_fs, 0) - - // @Param: RC_FS - // @DisplayName: Set time of RC failsafe - // @Description: if none of RC channel changes in that time, then failsafe triggers - // @Values: 0: turned off, >0 - time in seconds. Good values are starting 60s for digital protocols - // @User: Advanced - AP_GROUPINFO("RC_FS", 17, AP_Param_Helper, _rc_fs, 0) */ #ifdef USB_MASSSTORAGE #define BOARD_HAL_VARINFO \ - AP_GROUPINFO("MOTOR_LAYOUT", 1, AP_Param_Helper, _motor_layout, 0), \ - AP_GROUPINFO("SOFTSERIAL", 2, AP_Param_Helper, _use_softserial, 0), \ - AP_GROUPINFO("UART_SBUS", 3, AP_Param_Helper, _uart_sbus, 0), \ - AP_GROUPINFO("SERVO_MASK", 4, AP_Param_Helper, _servo_mask, 0), \ - AP_GROUPINFO("CONNECT_COM", 5, AP_Param_Helper, _connect_com, 0), \ - AP_GROUPINFO("PWM_TYPE", 7, AP_Param_Helper, _pwm_type, 0), \ - AP_GROUPINFO("CONNECT_ESC", 6, AP_Param_Helper, _connect_esc, 0), \ - AP_GROUPINFO("DBG_WAYBACK", 8, AP_Param_Helper, _dbg_wayback, 0), \ - AP_GROUPINFO("USB_STORAGE", 9, AP_Param_Helper, _usb_storage, 0), \ - AP_GROUPINFO("TIME_OFFSET", 10, AP_Param_Helper, _time_offset, 0), \ - AP_GROUPINFO("CONSOLE_UART", 11, AP_Param_Helper, _console_uart, HAL_CONSOLE_PORT), \ - AP_GROUPINFO("EE_DEFERRED", 12, AP_Param_Helper, _eeprom_deferred, 0), \ - AP_GROUPINFO("RC_INPUT", 13, AP_Param_Helper, _rc_input, 0), \ - AP_GROUPINFO("AIBAO_FS", 14, AP_Param_Helper, _aibao_fs, 0), \ - AP_GROUPINFO("OVERCLOCK", 15, AP_Param_Helper, _overclock, 0), \ - AP_GROUPINFO("CORRECT_GYRO", 16, AP_Param_Helper, _correct_gyro, 0), \ - AP_GROUPINFO("RC_FS", 17, AP_Param_Helper, _rc_fs, 0) + AP_GROUPINFO("DBG_WAYBACK", 30, AP_Param_Helper, _dbg_wayback, 0), \ + AP_GROUPINFO("USB_STORAGE", 31, AP_Param_Helper, _usb_storage, 0), \ #else #define BOARD_HAL_VARINFO \ - AP_GROUPINFO("MOTOR_LAYOUT", 1, AP_Param_Helper, _motor_layout, 0), \ - AP_GROUPINFO("SOFTSERIAL", 2, AP_Param_Helper, _use_softserial, 0), \ - AP_GROUPINFO("UART_SBUS", 3, AP_Param_Helper, _uart_sbus, 0), \ - AP_GROUPINFO("SERVO_MASK", 4, AP_Param_Helper, _servo_mask, 0), \ - AP_GROUPINFO("CONNECT_COM", 5, AP_Param_Helper, _connect_com, 0), \ - AP_GROUPINFO("PWM_TYPE", 7, AP_Param_Helper, _pwm_type, 0), \ - AP_GROUPINFO("CONNECT_ESC", 6, AP_Param_Helper, _connect_esc, 0), \ - AP_GROUPINFO("DBG_WAYBACK", 8, AP_Param_Helper, _dbg_wayback, 0), \ - AP_GROUPINFO("TIME_OFFSET", 9, AP_Param_Helper, _time_offset, 0), \ - AP_GROUPINFO("CONSOLE_UART", 10, AP_Param_Helper, _console_uart, HAL_CONSOLE_PORT), \ - AP_GROUPINFO("EE_DEFERRED", 11, AP_Param_Helper, _eeprom_deferred, 0), \ - AP_GROUPINFO("RC_INPUT", 12, AP_Param_Helper, _rc_input, 0), \ - AP_GROUPINFO("AIBAO_FS", 13, AP_Param_Helper, _aibao_fs, 0), \ - AP_GROUPINFO("OVERCLOCK", 14, AP_Param_Helper, _overclock, 0), \ - AP_GROUPINFO("CORRECT_GYRO", 15, AP_Param_Helper, _correct_gyro, 0), \ - AP_GROUPINFO("RC_FS", 16, AP_Param_Helper, _rc_fs, 0) + AP_GROUPINFO("DBG_WAYBACK", 30, AP_Param_Helper, _dbg_wayback, 0), \ #endif // parameters #define BOARD_HAL_PARAMS \ - AP_Int8 _motor_layout; \ - AP_Int8 _uart_sbus; \ - AP_Int8 _use_softserial; \ - AP_Int8 _servo_mask; \ - AP_Int8 _connect_com; \ - AP_Int8 _connect_esc; \ - AP_Int8 _pwm_type; \ AP_Int8 _dbg_wayback; \ - AP_Int8 _usb_storage; \ - AP_Int8 _time_offset; \ - AP_Int8 _console_uart; \ - AP_Int8 _eeprom_deferred; \ - AP_Int8 _rc_input; \ - AP_Int8 _aibao_fs; \ - AP_Int8 _overclock; \ - AP_Int8 _correct_gyro; \ - AP_Int8 _rc_fs; + AP_Int8 _usb_storage; #define WAYBACK_DEBUG diff --git a/libraries/AP_HAL_F4Light/boards/f4light_Airbot/support/UPLOAD-STLINK.sh b/libraries/AP_HAL_F4Light/boards/f4light_Airbot/support/UPLOAD-STLINK.sh index 1a2ba3a16a..c789f6c63e 100755 --- a/libraries/AP_HAL_F4Light/boards/f4light_Airbot/support/UPLOAD-STLINK.sh +++ b/libraries/AP_HAL_F4Light/boards/f4light_Airbot/support/UPLOAD-STLINK.sh @@ -5,8 +5,8 @@ #bare metal binary /usr/local/stlink/st-flash --reset read eeprom.bin 0x08004000 0xc000 && \ -/usr/local/stlink/st-flash --reset write ../../../../../ArduCopter/f4light_Airbot_bl.bin 0x08000000 && \ -/usr/local/stlink/st-flash --reset write eeprom.bin 0x08004000 && \ +/usr/local/stlink/st-flash --reset write ../../../../../ArduCopter/f4light_Airbot_bl.bin 0x08000000 +/usr/local/stlink/st-flash --reset write eeprom.bin 0x08004000 /usr/local/stlink/st-util -m diff --git a/libraries/AP_HAL_F4Light/boards/f4light_AirbotV2/board.cpp b/libraries/AP_HAL_F4Light/boards/f4light_AirbotV2/board.cpp index 892b9c02e4..a24fa957b4 100644 --- a/libraries/AP_HAL_F4Light/boards/f4light_AirbotV2/board.cpp +++ b/libraries/AP_HAL_F4Light/boards/f4light_AirbotV2/board.cpp @@ -165,10 +165,10 @@ extern const struct TIM_Channel PWM_Channels[] __FLASH__ = { */ extern const SPIDesc spi_device_table[] = { // different SPI tables per board subtype // name device bus mode cs_pin speed_low speed_high dma priority - { BOARD_INS_MPU60x0_NAME, _SPI1, 1, SPI_MODE_0, BOARD_MPU6000_CS_PIN, SPI_1_125MHZ, SPI_9MHZ, SPI_TRANSFER_DMA, DMA_Priority_VeryHigh, 1, 5 }, - { BOARD_SDCARD_NAME, _SPI2, 2, SPI_MODE_0, 255, SPI_1_125MHZ, SPI_18MHZ, SPI_TRANSFER_DMA, DMA_Priority_Medium, 0, 0 }, - { HAL_BARO_BMP280_NAME, _SPI3, 3, SPI_MODE_3, BOARD_BMP280_CS_PIN, SPI_1_125MHZ, SPI_9MHZ, SPI_TRANSFER_DMA, DMA_Priority_High, 1, 1 }, - { BOARD_OSD_NAME, _SPI3, 3, SPI_MODE_0, BOARD_OSD_CS_PIN, SPI_1_125MHZ, SPI_4_5MHZ, SPI_TRANSFER_DMA, DMA_Priority_Low, 2, 2 }, + { BOARD_INS_MPU60x0_NAME, _SPI1, 1, SPI_MODE_0, BOARD_MPU6000_CS_PIN, SPI_1_125MHZ, SPI_9MHZ, SPI_TRANSFER_DMA, DMA_Priority_VeryHigh, 1, 5 }, + { BOARD_SDCARD_NAME, _SPI2, 2, SPI_MODE_0, 255, SPI_1_125MHZ, SPI_18MHZ, SPI_TRANSFER_DMA, DMA_Priority_Medium, 0, 0 }, + { HAL_BARO_BMP280_NAME, _SPI3, 3, SPI_MODE_3, BOARD_BMP280_CS_PIN, SPI_1_125MHZ, SPI_9MHZ, SPI_TRANSFER_DMA, DMA_Priority_High, 1, 1 }, + { BOARD_OSD_NAME, _SPI3, 3, SPI_MODE_0, BOARD_OSD_CS_PIN, SPI_1_125MHZ, SPI_4_5MHZ, SPI_TRANSFER_DMA, DMA_Priority_Low, 2, 2 }, }; extern const uint8_t F4Light_SPI_DEVICE_NUM_DEVICES = ARRAY_SIZE(spi_device_table); diff --git a/libraries/AP_HAL_F4Light/boards/f4light_AirbotV2/board.h b/libraries/AP_HAL_F4Light/boards/f4light_AirbotV2/board.h index 046645f7d1..930fb565ba 100644 --- a/libraries/AP_HAL_F4Light/boards/f4light_AirbotV2/board.h +++ b/libraries/AP_HAL_F4Light/boards/f4light_AirbotV2/board.h @@ -177,61 +177,6 @@ /* - // @Param: MOTOR_LAYOUT - // @DisplayName: Motor layout scheme - // @Description: Selects how motors are numbered - // @Values: 0:ArduCopter, 1: Ardupilot with pins 2&3 for servos 2:OpenPilot,3:CleanFlight - // @User: Advanced - AP_GROUPINFO("_MOTOR_LAYOUT", 0, HAL_F4Light, _motor_layout, 0), - - // @Param: USE_SOFTSERIAL - // @DisplayName: Use SoftwareSerial driver - // @Description: Use SoftwareSerial driver instead SoftwareI2C on Input Port pins 7 & 8 - // @Values: 0:disabled,1:enabled - // @User: Advanced - AP_GROUPINFO("_USE_SOFTSERIAL", 1, HAL_F4Light, _use_softserial, 0), - - // @Param: UART_SBUS - // @DisplayName: What UART to use as SBUS input - // @Description: Allows to use any UART as SBUS input - // @Values: 0:disabled,1:UART1, 2:UART2 etc - // @User: Advanced - AP_GROUPINFO("UART_SBUS", 3, AP_Param_Helper, _uart_sbus, 0), \ - - // @Param: SERVO_MASK - // @DisplayName: Servo Mask of Input port - // @Description: Enable selected pins of Input port to be used as Servo Out - // @Values: 0:disabled,1:enable pin3 (PPM_1), 2: enable pin4 (PPM_2), 4: enable pin5 (UART6_TX) , 8: enable pin6 (UART6_RX), 16: enable pin7, 32: enable pin8 - // @User: Advanced - AP_GROUPINFO("SERVO_MASK", 2, AP_Param_Helper, _servo_mask, 0) - - // @Param: RC_INPUT - // @DisplayName: Type of RC input - // @Description: allows to force specified RC input port - // @Values: 0:auto, 1:PPM1 (pin3), 2: PPM2 (pin4) etc - // @User: Advanced - AP_GROUPINFO("RC_INPUT", 9, AP_Param_Helper, _rc_input, 0) - - // @Param: CONNECT_COM - // @DisplayName: connect to COM port - // @Description: Allows to connect USB to arbitrary UART, thus allowing to configure devices on that UARTs. Auto-reset. - // @Values: 0:disabled, 1:connect to port 1, 2:connect to port 2, etc - // @User: Advanced - AP_GROUPINFO("CONNECT_COM", 2, AP_Param_Helper, _connect_com, 0) \ - - // @Param: CONNECT_ESC - // @DisplayName: connect to ESC inputs via 4wayIf - // @Description: Allows to connect USB to ESC inputs, thus allowing to configure ESC as on 4-wayIf. Auto-reset. - // @Values: 0:disabled, 1:connect uartA to ESC, 2: connect uartB to ESC, etc - // @User: Advanced - AP_GROUPINFO("CONNECT_ESC", 2, AP_Param_Helper, _connect_esc, 0) \ - - // @Param: PWM_TYPE - // @DisplayName: PWM protocol used - // @Description: Allows to ignore MOT_PWM_TYPE param and set PWM protocol independently - // @Values: 0:use MOT_PWM_TYPE, 1:OneShot 2:OneShot125 3:OneShot42 4:PWM125 - // @User: Advanced - AP_GROUPINFO("PWM_TYPE", 7, AP_Param_Helper, _pwm_type, 0) // @Param: USB_STORAGE // @DisplayName: allows access to SD card at next reboot @@ -240,20 +185,6 @@ // @User: Advanced AP_GROUPINFO("USB_STORAGE", 8, AP_Param_Helper, _usb_storage, 0), \ - // @Param: EE_DEFERRED - // @DisplayName: Emulated EEPROM write mode - // @Description: Allows to control when changes to EEPROM are saved - ASAP or on disarm - // @Values: 0: save changes ASAP, 1:save changes on disarm. All changes will be lost in case of crash! - // @User: Advanced - AP_GROUPINFO("EE_DEFERRED", 7, AP_Param_Helper, _eeprom_deferred, 0), - - // @Param: AIBAO_FS - // @DisplayName: Support FailSafe for Walkera Aibao RC - // @Description: Allows to translate of Walkera Aibao RC FailSafe to Ardupilot's failsafe - // @Values: 0: not translate, 1:translate - // @User: Advanced - AP_GROUPINFO("AIBAO_FS", 7, AP_Param_Helper, _aibao_fs, 0), - // @Param: SD_REFORMAT // @DisplayName: Allows to re-format SD card in case of errors in FS // @Description: Any FS errors that cause failure of logging will be corrected by SD card formatting @@ -261,60 +192,16 @@ // @User: Advanced AP_GROUPINFO("SD_REFORMAT", 7, AP_Param_Helper, _sd_format, 0), - // @Param: OVERCLOCK - // @DisplayName: Set CPU frequency - // @Description: Allows to set overclocking frequency for CPU. If anything went wrong then normal freq will be restored after reboot - // @Values: 0: standard 168MHz, 1:180MHz, 2:192MHz, 3:216MHz, 4:240MHz, 5:264MHz - // @User: Advanced - AP_GROUPINFO("OVERCLOCK", 7, AP_Param_Helper, _overclock, 0), - - // @Param: RC_FS - // @DisplayName: Set time of RC failsafe - // @Description: if none of RC channel changes in that time, then failsafe triggers - // @Values: 0: turned off, >0 - time in seconds. Good values are starting 60s for digital protocols - // @User: Advanced - AP_GROUPINFO("RC_FS", 17, AP_Param_Helper, _rc_fs, 0) - */ #define BOARD_HAL_VARINFO \ - AP_GROUPINFO("MOTOR_LAYOUT", 1, AP_Param_Helper, _motor_layout, 0), \ - AP_GROUPINFO("SERVO_MASK", 2, AP_Param_Helper, _servo_mask, 0), \ - AP_GROUPINFO("UART_SBUS", 3, AP_Param_Helper, _uart_sbus, 0), \ - AP_GROUPINFO("SOFTSERIAL", 4, AP_Param_Helper, _use_softserial, 0), \ - AP_GROUPINFO("CONNECT_COM", 5, AP_Param_Helper, _connect_com, 0), \ - AP_GROUPINFO("PWM_TYPE", 6, AP_Param_Helper, _pwm_type, 0), \ - AP_GROUPINFO("CONNECT_ESC", 7, AP_Param_Helper, _connect_esc, 0), \ AP_GROUPINFO("USB_STORAGE", 8, AP_Param_Helper, _usb_storage, 0), \ - AP_GROUPINFO("TIME_OFFSET", 9, AP_Param_Helper, _time_offset, 0), \ - AP_GROUPINFO("CONSOLE_UART", 10, AP_Param_Helper, _console_uart, HAL_CONSOLE_PORT), \ - AP_GROUPINFO("EE_DEFERRED", 11, AP_Param_Helper, _eeprom_deferred, 0), \ - AP_GROUPINFO("RC_INPUT", 12, AP_Param_Helper, _rc_input, 0), \ - AP_GROUPINFO("AIBAO_FS", 13, AP_Param_Helper, _aibao_fs, 0), \ - AP_GROUPINFO("RC_FS", 14, AP_Param_Helper, _rc_fs, 0), \ - AP_GROUPINFO("OVERCLOCK", 15, AP_Param_Helper, _overclock, 0), \ - AP_GROUPINFO("CORRECT_GYRO", 16, AP_Param_Helper, _correct_gyro, 0), \ - AP_GROUPINFO("SD_REFORMAT", 17, AP_Param_Helper, _sd_format, 0) + AP_GROUPINFO("SD_REFORMAT", 17, AP_Param_Helper, _sd_format, 0), // parameters #define BOARD_HAL_PARAMS \ - AP_Int8 _motor_layout; \ - AP_Int8 _use_softserial; \ - AP_Int8 _uart_sbus; \ - AP_Int8 _servo_mask; \ - AP_Int8 _connect_com; \ - AP_Int8 _connect_esc; \ - AP_Int8 _pwm_type; \ - AP_Int8 _rc_input; \ - AP_Int8 _time_offset; \ - AP_Int8 _console_uart; \ - AP_Int8 _eeprom_deferred; \ AP_Int8 _usb_storage; \ - AP_Int8 _sd_format; \ - AP_Int8 _aibao_fs; \ - AP_Int8 _overclock; \ - AP_Int8 _correct_gyro; \ - AP_Int8 _rc_fs; + AP_Int8 _sd_format; #endif diff --git a/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/board.h b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/board.h index 7da8bd95f4..df23f7c4cd 100644 --- a/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/board.h +++ b/libraries/AP_HAL_F4Light/boards/f4light_MatekF405_OSD/board.h @@ -174,61 +174,6 @@ /* - // @Param: MOTOR_LAYOUT - // @DisplayName: Motor layout scheme - // @Description: Selects how motors are numbered - // @Values: 0:ArduCopter, 1: Ardupilot with pins 2&3 for servos 2:OpenPilot,3:CleanFlight - // @User: Advanced - AP_GROUPINFO("_MOTOR_LAYOUT", 0, HAL_F4Light, _motor_layout, 0), - - // @Param: USE_SOFTSERIAL - // @DisplayName: Use SoftwareSerial driver - // @Description: Use SoftwareSerial driver instead SoftwareI2C on Input Port pins 7 & 8 - // @Values: 0:disabled,1:enabled - // @User: Advanced - AP_GROUPINFO("_USE_SOFTSERIAL", 1, HAL_F4Light, _use_softserial, 0), - - // @Param: UART_SBUS - // @DisplayName: What UART to use as SBUS input - // @Description: Allows to use any UART as SBUS input - // @Values: 0:disabled,1:UART1, 2:UART2 etc - // @User: Advanced - AP_GROUPINFO("UART_SBUS", 3, AP_Param_Helper, _uart_sbus, 0), \ - - // @Param: SERVO_MASK - // @DisplayName: Servo Mask of Input port - // @Description: Enable selected pins of Input port to be used as Servo Out - // @Values: 0:disabled,1:enable pin3 (PPM_1), 2: enable pin4 (PPM_2), 4: enable pin5 (UART6_TX) , 8: enable pin6 (UART6_RX), 16: enable pin7, 32: enable pin8 - // @User: Advanced - AP_GROUPINFO("SERVO_MASK", 2, AP_Param_Helper, _servo_mask, 0) - - // @Param: RC_INPUT - // @DisplayName: Type of RC input - // @Description: allows to force specified RC input port - // @Values: 0:auto, 1:PPM1 (pin3), 2: PPM2 (pin4) etc - // @User: Advanced - AP_GROUPINFO("RC_INPUT", 9, AP_Param_Helper, _rc_input, 0) - - // @Param: CONNECT_COM - // @DisplayName: connect to COM port - // @Description: Allows to connect USB to arbitrary UART, thus allowing to configure devices on that UARTs. Auto-reset. - // @Values: 0:disabled, 1:connect to port 1, 2:connect to port 2, etc - // @User: Advanced - AP_GROUPINFO("CONNECT_COM", 2, AP_Param_Helper, _connect_com, 0) \ - - // @Param: CONNECT_ESC - // @DisplayName: connect to ESC inputs via 4wayIf - // @Description: Allows to connect USB to ESC inputs, thus allowing to configure ESC as on 4-wayIf. Auto-reset. - // @Values: 0:disabled, 1:connect uartA to ESC, 2: connect uartB to ESC, etc - // @User: Advanced - AP_GROUPINFO("CONNECT_ESC", 2, AP_Param_Helper, _connect_esc, 0) \ - - // @Param: PWM_TYPE - // @DisplayName: PWM protocol used - // @Description: Allows to ignore MOT_PWM_TYPE param and set PWM protocol independently - // @Values: 0:use MOT_PWM_TYPE, 1:OneShot 2:OneShot125 3:OneShot42 4:PWM125 - // @User: Advanced - AP_GROUPINFO("PWM_TYPE", 7, AP_Param_Helper, _pwm_type, 0) // @Param: USB_STORAGE // @DisplayName: allows access to SD card at next reboot @@ -237,20 +182,6 @@ // @User: Advanced AP_GROUPINFO("USB_STORAGE", 8, AP_Param_Helper, _usb_storage, 0), \ - // @Param: EE_DEFERRED - // @DisplayName: Emulated EEPROM write mode - // @Description: Allows to control when changes to EEPROM are saved - ASAP or on disarm - // @Values: 0: save changes ASAP, 1:save changes on disarm. All changes will be lost in case of crash! - // @User: Advanced - AP_GROUPINFO("EE_DEFERRED", 7, AP_Param_Helper, _eeprom_deferred, 0), - - // @Param: AIBAO_FS - // @DisplayName: Support FailSafe for Walkera Aibao RC - // @Description: Allows to translate of Walkera Aibao RC FailSafe to Ardupilot's failsafe - // @Values: 0: not translate, 1:translate - // @User: Advanced - AP_GROUPINFO("AIBAO_FS", 7, AP_Param_Helper, _aibao_fs, 0), - // @Param: SD_REFORMAT // @DisplayName: Allows to re-format SD card in case of errors in FS // @Description: Any FS errors that cause failure of logging will be corrected by SD card formatting @@ -258,55 +189,16 @@ // @User: Advanced AP_GROUPINFO("SD_REFORMAT", 7, AP_Param_Helper, _sd_format, 0), - // @Param: OVERCLOCK - // @DisplayName: Set CPU frequency - // @Description: Allows to set overclocking frequency for CPU. If anything went wrong then normal freq will be restored after reboot - // @Values: 0: standard 168MHz, 1:180MHz, 2:192MHz, 3:216MHz, 4:240MHz, 5:264MHz - // @User: Advanced - AP_GROUPINFO("OVERCLOCK", 7, AP_Param_Helper, _overclock, 0), - - */ #define BOARD_HAL_VARINFO \ - AP_GROUPINFO("MOTOR_LAYOUT", 1, AP_Param_Helper, _motor_layout, 0), \ - AP_GROUPINFO("SERVO_MASK", 2, AP_Param_Helper, _servo_mask, 0), \ - AP_GROUPINFO("UART_SBUS", 3, AP_Param_Helper, _uart_sbus, 0), \ - AP_GROUPINFO("SOFTSERIAL", 4, AP_Param_Helper, _use_softserial, 0), \ - AP_GROUPINFO("CONNECT_COM", 5, AP_Param_Helper, _connect_com, 0), \ - AP_GROUPINFO("PWM_TYPE", 6, AP_Param_Helper, _pwm_type, 0), \ - AP_GROUPINFO("CONNECT_ESC", 7, AP_Param_Helper, _connect_esc, 0), \ - AP_GROUPINFO("USB_STORAGE", 8, AP_Param_Helper, _usb_storage, 0), \ - AP_GROUPINFO("TIME_OFFSET", 9, AP_Param_Helper, _time_offset, 0), \ - AP_GROUPINFO("CONSOLE_UART", 10, AP_Param_Helper, _console_uart, HAL_CONSOLE_PORT), \ - AP_GROUPINFO("EE_DEFERRED", 11, AP_Param_Helper, _eeprom_deferred, 0), \ - AP_GROUPINFO("RC_INPUT", 12, AP_Param_Helper, _rc_input, 0), \ - AP_GROUPINFO("AIBAO_FS", 13, AP_Param_Helper, _aibao_fs, 0), \ - AP_GROUPINFO("RC_FS", 14, AP_Param_Helper, _rc_fs, 0), \ - AP_GROUPINFO("OVERCLOCK", 15, AP_Param_Helper, _overclock, 0), \ - AP_GROUPINFO("CORRECT_GYRO", 16, AP_Param_Helper, _correct_gyro, 0), \ - AP_GROUPINFO("SD_REFORMAT", 17, AP_Param_Helper, _sd_format, 0) + AP_GROUPINFO("USB_STORAGE", 30, AP_Param_Helper, _usb_storage, 0), \ + AP_GROUPINFO("SD_REFORMAT", 31, AP_Param_Helper, _sd_format, 0), // parameters #define BOARD_HAL_PARAMS \ - AP_Int8 _motor_layout; \ - AP_Int8 _use_softserial; \ - AP_Int8 _uart_sbus; \ - AP_Int8 _servo_mask; \ - AP_Int8 _connect_com; \ - AP_Int8 _connect_esc; \ - AP_Int8 _pwm_type; \ - AP_Int8 _rc_input; \ - AP_Int8 _time_offset; \ - AP_Int8 _console_uart; \ - AP_Int8 _eeprom_deferred; \ AP_Int8 _usb_storage; \ - AP_Int8 _sd_format; \ - AP_Int8 _aibao_fs; \ - AP_Int8 _overclock; \ - AP_Int8 _correct_gyro; \ - AP_Int8 _rc_fs; - + AP_Int8 _sd_format; #endif diff --git a/libraries/AP_HAL_F4Light/boards/f4light_MiniF4_OSD/board.h b/libraries/AP_HAL_F4Light/boards/f4light_MiniF4_OSD/board.h index 5d662c0311..e7d991db5b 100644 --- a/libraries/AP_HAL_F4Light/boards/f4light_MiniF4_OSD/board.h +++ b/libraries/AP_HAL_F4Light/boards/f4light_MiniF4_OSD/board.h @@ -157,62 +157,6 @@ /* - // @Param: MOTOR_LAYOUT - // @DisplayName: Motor layout scheme - // @Description: Selects how motors are numbered - // @Values: 0:ArduCopter, 1: Ardupilot with pins 2&3 for servos 2:OpenPilot,3:CleanFlight - // @User: Advanced - AP_GROUPINFO("_MOTOR_LAYOUT", 0, HAL_F4Light, _motor_layout, 0), - - // @Param: USE_SOFTSERIAL - // @DisplayName: Use SoftwareSerial driver - // @Description: Use SoftwareSerial driver instead SoftwareI2C on Input Port pins 7 & 8 - // @Values: 0:disabled,1:enabled - // @User: Advanced - AP_GROUPINFO("_USE_SOFTSERIAL", 1, HAL_F4Light, _use_softserial, 0), - - // @Param: UART_SBUS - // @DisplayName: What UART to use as SBUS input - // @Description: Allows to use any UART as SBUS input - // @Values: 0:disabled,1:UART1, 2:UART2 etc - // @User: Advanced - AP_GROUPINFO("UART_SBUS", 3, AP_Param_Helper, _uart_sbus, 0), \ - - // @Param: SERVO_MASK - // @DisplayName: Servo Mask of Input port - // @Description: Enable selected pins of Input port to be used as Servo Out - // @Values: 0:disabled,1:enable pin3 (PPM_1), 2: enable pin4 (PPM_2), 4: enable pin5 (UART6_TX) , 8: enable pin6 (UART6_RX), 16: enable pin7, 32: enable pin8 - // @User: Advanced - AP_GROUPINFO("SERVO_MASK", 2, AP_Param_Helper, _servo_mask, 0) - - // @Param: RC_INPUT - // @DisplayName: Type of RC input - // @Description: allows to force specified RC input port - // @Values: 0:auto, 1:PPM1 (pin3), 2: PPM2 (pin4) etc - // @User: Advanced - AP_GROUPINFO("RC_INPUT", 9, AP_Param_Helper, _rc_input, 0) - - // @Param: CONNECT_COM - // @DisplayName: connect to COM port - // @Description: Allows to connect USB to arbitrary UART, thus allowing to configure devices on that UARTs. Auto-reset. - // @Values: 0:disabled, 1:connect to port 1, 2:connect to port 2, etc - // @User: Advanced - AP_GROUPINFO("CONNECT_COM", 2, AP_Param_Helper, _connect_com, 0) \ - - // @Param: CONNECT_ESC - // @DisplayName: connect to ESC inputs via 4wayIf - // @Description: Allows to connect USB to ESC inputs, thus allowing to configure ESC as on 4-wayIf. Auto-reset. - // @Values: 0:disabled, 1:connect uartA to ESC, 2: connect uartB to ESC, etc - // @User: Advanced - AP_GROUPINFO("CONNECT_ESC", 2, AP_Param_Helper, _connect_esc, 0) \ - - // @Param: PWM_TYPE - // @DisplayName: PWM protocol used - // @Description: Allows to ignore MOT_PWM_TYPE param and set PWM protocol independently - // @Values: 0:use MOT_PWM_TYPE, 1:OneShot 2:OneShot125 3:OneShot42 4:PWM125 - // @User: Advanced - AP_GROUPINFO("PWM_TYPE", 7, AP_Param_Helper, _pwm_type, 0) - // @Param: USB_STORAGE // @DisplayName: allows access to SD card at next reboot // @Description: Allows to read/write internal SD card via USB mass-storage protocol. Auto-reset. @@ -220,50 +164,15 @@ // @User: Advanced AP_GROUPINFO("USB_STORAGE", 8, AP_Param_Helper, _usb_storage, 0), \ - // @Param: RC_FS - // @DisplayName: Set time of RC failsafe - // @Description: if none of RC channel changes in that time, then failsafe triggers - // @Values: 0: turned off, >0 - time in seconds. Good values are starting 60s for digital protocols - // @User: Advanced - AP_GROUPINFO("RC_FS", 17, AP_Param_Helper, _rc_fs, 0) */ #define BOARD_HAL_VARINFO \ - AP_GROUPINFO("MOTOR_LAYOUT", 1, AP_Param_Helper, _motor_layout, 0), \ - AP_GROUPINFO("SERVO_MASK", 2, AP_Param_Helper, _servo_mask, 0), \ - AP_GROUPINFO("UART_SBUS", 3, AP_Param_Helper, _uart_sbus, 0), \ - AP_GROUPINFO("CONNECT_COM", 5, AP_Param_Helper, _connect_com, 0), \ - AP_GROUPINFO("PWM_TYPE", 6, AP_Param_Helper, _pwm_type, 0), \ - AP_GROUPINFO("CONNECT_ESC", 7, AP_Param_Helper, _connect_esc, 0), \ - AP_GROUPINFO("USB_STORAGE", 8, AP_Param_Helper, _usb_storage, 0), \ - AP_GROUPINFO("TIME_OFFSET", 9, AP_Param_Helper, _time_offset, 0), \ - AP_GROUPINFO("CONSOLE_UART", 10, AP_Param_Helper, _console_uart, HAL_CONSOLE_PORT), \ - AP_GROUPINFO("EE_DEFERRED", 11, AP_Param_Helper, _eeprom_deferred, 0), \ - AP_GROUPINFO("RC_INPUT", 12, AP_Param_Helper, _rc_input, 0), \ - AP_GROUPINFO("AIBAO_FS", 13, AP_Param_Helper, _aibao_fs, 0), \ - AP_GROUPINFO("OVERCLOCK", 14, AP_Param_Helper, _overclock, 0), \ - AP_GROUPINFO("CORRECT_GYRO", 15, AP_Param_Helper, _correct_gyro, 0), \ - AP_GROUPINFO("RC_FS", 16, AP_Param_Helper, _rc_fs, 0) + AP_GROUPINFO("USB_STORAGE", 30, AP_Param_Helper, _usb_storage, 0), // parameters #define BOARD_HAL_PARAMS \ - AP_Int8 _motor_layout; \ - AP_Int8 _uart_sbus; \ - AP_Int8 _servo_mask; \ - AP_Int8 _connect_com; \ - AP_Int8 _connect_esc; \ - AP_Int8 _pwm_type; \ - AP_Int8 _rc_input; \ - AP_Int8 _time_offset; \ - AP_Int8 _console_uart; \ - AP_Int8 _eeprom_deferred; \ - AP_Int8 _usb_storage; \ - AP_Int8 _aibao_fs; \ - AP_Int8 _overclock; \ - AP_Int8 _correct_gyro; \ - AP_Int8 _rc_fs; - -#endif + AP_Int8 _usb_storage; #define USB_MASSSTORAGE +#endif diff --git a/libraries/AP_HAL_F4Light/boards/f4light_Revolution/board.h b/libraries/AP_HAL_F4Light/boards/f4light_Revolution/board.h index a4b4b1bc35..6309f48c08 100644 --- a/libraries/AP_HAL_F4Light/boards/f4light_Revolution/board.h +++ b/libraries/AP_HAL_F4Light/boards/f4light_Revolution/board.h @@ -192,48 +192,6 @@ #define HAL_CONSOLE_PORT 1 // console on radio /* - // @Param: MOTOR_LAYOUT - // @DisplayName: Motor layout scheme - // @Description: Selects how motors are numbered - // @Values: 0:ArduCopter, 1: Ardupilot with pins 2&3 for servos 2:OpenPilot,3:CleanFlight - // @User: Advanced - AP_GROUPINFO("_MOTOR_LAYOUT", 0, HAL_F4Light, _motor_layout, 0), - - // @Param: UART_SBUS - // @DisplayName: What UART to use as SBUS input - // @Description: Allows to use any UART as SBUS input - // @Values: 0:disabled,1:UART1(Main port) - // @User: Advanced - AP_GROUPINFO("UART_SBUS", 3, AP_Param_Helper, _uart_sbus, 0), \ - - // @Param: USE_SOFTSERIAL - // @DisplayName: Use SoftwareSerial driver - // @Description: Use SoftwareSerial driver instead SoftwareI2C on Input Port pins 7 & 8 - // @Values: 0:disabled,1:enabled - // @User: Advanced - AP_GROUPINFO("_USE_SOFTSERIAL", 1, HAL_F4Light, _use_softserial, 0), - - // @Param: SERVO_MASK - // @DisplayName: Servo Mask of Input port - // @Description: Enable selected pins of Input port to be used as Servo Out - // @Values: 0:disabled,1:enable pin3 (PPM_1), 2: enable pin4 (PPM_2), 4: enable pin5 (UART6_TX) , 8: enable pin6 (UART6_RX), 16: enable pin7, 32: enable pin8 - // @User: Advanced - AP_GROUPINFO("SERVO_MASK", 2, AP_Param_Helper, _servo_mask, 0) \ - - // @Param: CONNECT_COM - // @DisplayName: connect to COM port - // @Description: Allows to connect USB to arbitrary Serial Port, thus allowing to configure devices on that Serial Ports. Auto-reset. - // @Values: 0:disabled, 1:connect to Serial1, 2:connect to Serial2, etc - // @User: Advanced - AP_GROUPINFO("CONNECT_COM", 2, AP_Param_Helper, _connect_com, 0) \ - - // @Param: CONNECT_ESC - // @DisplayName: connect to ESC inputs via 4wayIf - // @Description: Allows to connect USB to ESC inputs, thus allowing to configure ESC as on 4-wayIf. Auto-reset. - // @Values: 0:disabled, 1:connect uartA to ESC, 2: connect uartB to ESC, etc - // @User: Advanced - AP_GROUPINFO("CONNECT_ESC", 2, AP_Param_Helper, _connect_esc, 0) \ - // @Param: FLEXI_I2C // @DisplayName: use FlexiPort as I2C, not USART // @Description: Allows to switch FlexiPort usage between USART and I2C modes @@ -241,102 +199,15 @@ // @User: Advanced AP_GROUPINFO("FLEXI_I2C", 6, AP_Param_Helper, _flexi_i2c, 0) \ - // @Param: PWM_TYPE - // @DisplayName: PWM protocol used - // @Description: Allows to ignore MOT_PWM_TYPE param and set PWM protocol independently - // @Values: 0:use MOT_PWM_TYPE, 1:OneShot 2:OneShot125 3:OneShot42 4:PWM125 - // @User: Advanced - AP_GROUPINFO("PWM_TYPE", 7, AP_Param_Helper, _pwm_type, 0) - - - // @Param: TIME_OFFSET - // @DisplayName: offset from GMT time - // @Description: Allows to see local date & time in logs - // @Values: -11..+11 - AP_GROUPINFO("TIME_OFFSET", 10, AP_Param_Helper, _time_offset, 0), \ - - // @Param: CONSOLE_UART - // @DisplayName: number of port to use as console - // @Description: Allows to specify console port - // @Values: 0:USB, 1:connect to UART 1, 2:connect to UART 2, etc - AP_GROUPINFO("CONSOLE_UART", 11, AP_Param_Helper, _console_uart, 0), \ - - - // @Param: RC_INPUT - // @DisplayName: Type of RC input - // @Description: allows to force specified RC input poty - // @Values: 0:auto, 1:PPM1 (pin3), 2: PPM2 (pin4) etc - // @User: Advanced - AP_GROUPINFO("RC_INPUT", 9, AP_Param_Helper, _rc_input, 0) - - // @Param: EE_DEFERRED - // @DisplayName: Emulated EEPROM write mode - // @Description: Allows to control when changes to EEPROM are saved - ASAP or on disarm - // @Values: 0: save changes ASAP, 1:save changes on disarm. All changes will be lost in case of crash! - // @User: Advanced - AP_GROUPINFO("EE_DEFERRED", 7, AP_Param_Helper, _eeprom_deferred, 0) - - // @Param: AIBAO_FS - // @DisplayName: Support FailSafe for Walkera Aibao RC - // @Description: Allows to translate of Walkera Aibao RC FailSafe to Ardupilot's failsafe - // @Values: 0: not translate, 1:translate - // @User: Advanced - AP_GROUPINFO("AIBAO_FS", 7, AP_Param_Helper, _aibao_fs, 0) - - // @Param: OVERCLOCK - // @DisplayName: Set CPU frequency - // @Description: Allows to set overclocking frequency for CPU. If anything went wrong then normal freq will be restored after reboot - // @Values: 0: standard 168MHz, 1:180MHz, 2:192MHz, 3:216MHz, 4:240MHz(*), 5:264MHz - // @User: Advanced - AP_GROUPINFO("OVERCLOCK", 7, AP_Param_Helper, _overclock, 0), - - // @Param: RC_FS - // @DisplayName: Set time of RC failsafe - // @Description: if none of RC channel changes in that time, then failsafe triggers - // @Values: 0: turned off, >0 - time in seconds. Good values are starting 60s for digital protocols - // @User: Advanced - AP_GROUPINFO("RC_FS", 17, AP_Param_Helper, _rc_fs, 0) */ #define BOARD_HAL_VARINFO \ - AP_GROUPINFO("MOTOR_LAYOUT", 1, AP_Param_Helper, _motor_layout, 0), \ - AP_GROUPINFO("SERVO_MASK", 2, AP_Param_Helper, _servo_mask, 0), \ - AP_GROUPINFO("UART_SBUS", 3, AP_Param_Helper, _uart_sbus, 0), \ - AP_GROUPINFO("SOFTSERIAL", 4, AP_Param_Helper, _use_softserial, 0), \ - AP_GROUPINFO("CONNECT_COM", 5, AP_Param_Helper, _connect_com, 0), \ - AP_GROUPINFO("CONNECT_ESC", 6, AP_Param_Helper, _connect_esc, 0), \ - AP_GROUPINFO("FLEXI_I2C", 7, AP_Param_Helper, _flexi_i2c, 0), \ - AP_GROUPINFO("PWM_TYPE", 8, AP_Param_Helper, _pwm_type, 0), \ - AP_GROUPINFO("USB_STORAGE", 10, AP_Param_Helper, _usb_storage, 0), \ - AP_GROUPINFO("TIME_OFFSET", 11, AP_Param_Helper, _time_offset, 0), \ - AP_GROUPINFO("CONSOLE_UART", 12, AP_Param_Helper, _console_uart, HAL_CONSOLE_PORT), \ - AP_GROUPINFO("EE_DEFERRED", 13, AP_Param_Helper, _eeprom_deferred, 0), \ - AP_GROUPINFO("RC_INPUT", 14, AP_Param_Helper, _rc_input, 0), \ - AP_GROUPINFO("AIBAO_FS", 15, AP_Param_Helper, _aibao_fs, 0), \ - AP_GROUPINFO("OVERCLOCK", 16, AP_Param_Helper, _overclock, 0), \ - AP_GROUPINFO("CORRECT_GYRO", 17, AP_Param_Helper, _correct_gyro, 0), \ - AP_GROUPINFO("RC_FS", 18, AP_Param_Helper, _rc_fs, 0) + AP_GROUPINFO("FLEXI_I2C", 30, AP_Param_Helper, _flexi_i2c, 0), // parameters #define BOARD_HAL_PARAMS \ - AP_Int8 _motor_layout; \ - AP_Int8 _use_softserial; \ - AP_Int8 _servo_mask; \ - AP_Int8 _connect_com; \ - AP_Int8 _connect_esc; \ - AP_Int8 _uart_sbus; \ - AP_Int8 _flexi_i2c; \ - AP_Int8 _pwm_type; \ - AP_Int8 _usb_storage; \ - AP_Int8 _time_offset; \ - AP_Int8 _console_uart; \ - AP_Int8 _eeprom_deferred; \ - AP_Int8 _rc_input; \ - AP_Int8 _aibao_fs; \ - AP_Int8 _overclock; \ - AP_Int8 _correct_gyro; \ - AP_Int8 _rc_fs; + AP_Int8 _flexi_i2c; #define ERROR_USART _USART1 // main port - telemetry, all panic messages goes there diff --git a/libraries/AP_HAL_F4Light/boards/f4light_cl_racing/board.h b/libraries/AP_HAL_F4Light/boards/f4light_cl_racing/board.h index c59a670180..ee8bbbb135 100644 --- a/libraries/AP_HAL_F4Light/boards/f4light_cl_racing/board.h +++ b/libraries/AP_HAL_F4Light/boards/f4light_cl_racing/board.h @@ -181,63 +181,6 @@ #endif /* - - // @Param: MOTOR_LAYOUT - // @DisplayName: Motor layout scheme - // @Description: Selects how motors are numbered - // @Values: 0:ArduCopter, 1: Ardupilot with pins 2&3 for servos 2:OpenPilot,3:CleanFlight - // @User: Advanced - AP_GROUPINFO("_MOTOR_LAYOUT", 0, HAL_F4Light, _motor_layout, 0), - - // @Param: USE_SOFTSERIAL - // @DisplayName: Use SoftwareSerial driver - // @Description: Use SoftwareSerial driver instead SoftwareI2C on Input Port pins 7 & 8 - // @Values: 0:disabled,1:enabled - // @User: Advanced - AP_GROUPINFO("_USE_SOFTSERIAL", 1, HAL_F4Light, _use_softserial, 0), - - // @Param: UART_SBUS - // @DisplayName: What UART to use as SBUS input - // @Description: Allows to use any UART as SBUS input - // @Values: 0:disabled,1:UART1, 2:UART2 etc - // @User: Advanced - AP_GROUPINFO("UART_SBUS", 3, AP_Param_Helper, _uart_sbus, 0), \ - - // @Param: SERVO_MASK - // @DisplayName: Servo Mask of Input port - // @Description: Enable selected pins of Input port to be used as Servo Out - // @Values: 0:disabled,1:enable pin3 (PPM_1), 2: enable pin4 (PPM_2), 4: enable pin5 (UART6_TX) , 8: enable pin6 (UART6_RX), 16: enable pin7, 32: enable pin8 - // @User: Advanced - AP_GROUPINFO("SERVO_MASK", 2, AP_Param_Helper, _servo_mask, 0) - - // @Param: RC_INPUT - // @DisplayName: Type of RC input - // @Description: allows to force specified RC input port - // @Values: 0:auto, 1:PPM1 (pin3), 2: PPM2 (pin4) etc - // @User: Advanced - AP_GROUPINFO("RC_INPUT", 9, AP_Param_Helper, _rc_input, 0) - - // @Param: CONNECT_COM - // @DisplayName: connect to COM port - // @Description: Allows to connect USB to arbitrary UART, thus allowing to configure devices on that UARTs. Auto-reset. - // @Values: 0:disabled, 1:connect to port 1, 2:connect to port 2, etc - // @User: Advanced - AP_GROUPINFO("CONNECT_COM", 2, AP_Param_Helper, _connect_com, 0) \ - - // @Param: CONNECT_ESC - // @DisplayName: connect to ESC inputs via 4wayIf - // @Description: Allows to connect USB to ESC inputs, thus allowing to configure ESC as on 4-wayIf. Auto-reset. - // @Values: 0:disabled, 1:connect uartA to ESC, 2: connect uartB to ESC, etc - // @User: Advanced - AP_GROUPINFO("CONNECT_ESC", 2, AP_Param_Helper, _connect_esc, 0) \ - - // @Param: PWM_TYPE - // @DisplayName: PWM protocol used - // @Description: Allows to ignore MOT_PWM_TYPE param and set PWM protocol independently - // @Values: 0:use MOT_PWM_TYPE, 1:OneShot 2:OneShot125 3:OneShot42 4:PWM125 - // @User: Advanced - AP_GROUPINFO("PWM_TYPE", 7, AP_Param_Helper, _pwm_type, 0) - // @Param: USB_STORAGE // @DisplayName: allows access to SD card at next reboot // @Description: Allows to read/write internal SD card via USB mass-storage protocol. Auto-reset. @@ -245,81 +188,22 @@ // @User: Advanced AP_GROUPINFO("USB_STORAGE", 8, AP_Param_Helper, _usb_storage, 0), \ - // @Param: EE_DEFERRED - // @DisplayName: Emulated EEPROM write mode - // @Description: Allows to control when changes to EEPROM are saved - ASAP or on disarm - // @Values: 0: save changes ASAP, 1:save changes on disarm. All changes will be lost in case of crash! - // @User: Advanced - AP_GROUPINFO("EE_DEFERRED", 7, AP_Param_Helper, _eeprom_deferred, 0), - - // @Param: AIBAO_FS - // @DisplayName: Support FailSafe for Walkera Aibao RC - // @Description: Allows to translate of Walkera Aibao RC FailSafe to Ardupilot's failsafe - // @Values: 0: not translate, 1:translate - // @User: Advanced - AP_GROUPINFO("AIBAO_FS", 7, AP_Param_Helper, _aibao_fs, 0), - // @Param: SD_REFORMAT // @DisplayName: Allows to re-format SD card in case of errors in FS // @Description: Any FS errors that cause failure of logging will be corrected by SD card formatting // @Values: 0: not allow, 1:allow // @User: Advanced AP_GROUPINFO("SD_REFORMAT", 7, AP_Param_Helper, _sd_format, 0), - - // @Param: OVERCLOCK - // @DisplayName: Set CPU frequency - // @Description: Allows to set overclocking frequency for CPU. If anything went wrong then normal freq will be restored after reboot - // @Values: 0: standard 168MHz, 1:180MHz, 2:192MHz, 3:216MHz, 4:240MHz, 5:264MHz - // @User: Advanced - AP_GROUPINFO("OVERCLOCK", 7, AP_Param_Helper, _overclock, 0), - - // @Param: RC_FS - // @DisplayName: Set time of RC failsafe - // @Description: if none of RC channel changes in that time, then failsafe triggers - // @Values: 0: turned off, >0 - time in seconds. Good values are starting 60s for digital protocols - // @User: Advanced - AP_GROUPINFO("RC_FS", 17, AP_Param_Helper, _rc_fs, 0) - */ #define BOARD_HAL_VARINFO \ - AP_GROUPINFO("MOTOR_LAYOUT", 1, AP_Param_Helper, _motor_layout, 0), \ - AP_GROUPINFO("SERVO_MASK", 2, AP_Param_Helper, _servo_mask, 0), \ - AP_GROUPINFO("UART_SBUS", 3, AP_Param_Helper, _uart_sbus, 0), \ - AP_GROUPINFO("SOFTSERIAL", 4, AP_Param_Helper, _use_softserial, 0), \ - AP_GROUPINFO("CONNECT_COM", 5, AP_Param_Helper, _connect_com, 0), \ - AP_GROUPINFO("PWM_TYPE", 6, AP_Param_Helper, _pwm_type, 0), \ - AP_GROUPINFO("CONNECT_ESC", 7, AP_Param_Helper, _connect_esc, 0), \ - AP_GROUPINFO("USB_STORAGE", 8, AP_Param_Helper, _usb_storage, 0), \ - AP_GROUPINFO("TIME_OFFSET", 9, AP_Param_Helper, _time_offset, 0), \ - AP_GROUPINFO("CONSOLE_UART", 10, AP_Param_Helper, _console_uart, HAL_CONSOLE_PORT), \ - AP_GROUPINFO("EE_DEFERRED", 11, AP_Param_Helper, _eeprom_deferred, 0), \ - AP_GROUPINFO("RC_INPUT", 12, AP_Param_Helper, _rc_input, 0), \ - AP_GROUPINFO("AIBAO_FS", 13, AP_Param_Helper, _aibao_fs, 0), \ - AP_GROUPINFO("RC_FS", 14, AP_Param_Helper, _rc_fs, 0), \ - AP_GROUPINFO("OVERCLOCK", 15, AP_Param_Helper, _overclock, 0), \ - AP_GROUPINFO("CORRECT_GYRO", 16, AP_Param_Helper, _correct_gyro, 0), \ - AP_GROUPINFO("SD_REFORMAT", 17, AP_Param_Helper, _sd_format, 0) + AP_GROUPINFO("USB_STORAGE", 30, AP_Param_Helper, _usb_storage, 0), \ + AP_GROUPINFO("SD_REFORMAT", 31, AP_Param_Helper, _sd_format, 0), // parameters #define BOARD_HAL_PARAMS \ - AP_Int8 _motor_layout; \ - AP_Int8 _use_softserial; \ - AP_Int8 _uart_sbus; \ - AP_Int8 _servo_mask; \ - AP_Int8 _connect_com; \ - AP_Int8 _connect_esc; \ - AP_Int8 _pwm_type; \ - AP_Int8 _rc_input; \ - AP_Int8 _time_offset; \ - AP_Int8 _console_uart; \ - AP_Int8 _eeprom_deferred; \ AP_Int8 _usb_storage; \ - AP_Int8 _sd_format; \ - AP_Int8 _aibao_fs; \ - AP_Int8 _overclock; \ - AP_Int8 _correct_gyro; \ - AP_Int8 _rc_fs; + AP_Int8 _sd_format; #endif diff --git a/libraries/AP_HAL_F4Light/params.h b/libraries/AP_HAL_F4Light/params.h new file mode 100644 index 0000000000..562f8b4505 --- /dev/null +++ b/libraries/AP_HAL_F4Light/params.h @@ -0,0 +1,113 @@ + + +/* + // @Param: MOTOR_LAYOUT + // @DisplayName: Motor layout scheme + // @Description: Selects how motors are numbered + // @Values: 0:ArduCopter, 1: Ardupilot with pins 2&3 for servos 2:OpenPilot,3:CleanFlight + // @User: Advanced + AP_GROUPINFO("_MOTOR_LAYOUT", 0, HAL_F4Light, _motor_layout, 0), + + // @Param: USE_SOFTSERIAL + // @DisplayName: Use SoftwareSerial driver + // @Description: Use SoftwareSerial driver instead SoftwareI2C on Input Port pins 7 & 8 + // @Values: 0:disabled,1:enabled + // @User: Advanced + AP_GROUPINFO("_USE_SOFTSERIAL", 1, HAL_F4Light, _use_softserial, 0), + + // @Param: UART_SBUS + // @DisplayName: What UART to use as SBUS input + // @Description: Allows to use any UART as SBUS input + // @Values: 0:disabled,1:UART1, 2:UART2 etc + // @User: Advanced + AP_GROUPINFO("UART_SBUS", 3, AP_Param_Helper, _uart_sbus, 0), \ + + // @Param: SERVO_MASK + // @DisplayName: Servo Mask of Input port + // @Description: Enable selected pins of Input port to be used as Servo Out + // @Values: 0:disabled,1:enable pin3 (PPM_1), 2: enable pin4 (PPM_2), 4: enable pin5 (UART6_TX) , 8: enable pin6 (UART6_RX), 16: enable pin7, 32: enable pin8 + // @User: Advanced + AP_GROUPINFO("SERVO_MASK", 2, AP_Param_Helper, _servo_mask, 0) \ + + // @Param: CONNECT_COM + // @DisplayName: connect to COM port + // @Description: Allows to connect USB to arbitrary UART, thus allowing to configure devices on that UARTs. Auto-reset. + // @Values: 0:disabled, 1:connect to port 1, 2:connect to port 2, etc + // @User: Advanced + AP_GROUPINFO("CONNECT_COM", 2, AP_Param_Helper, _connect_com, 0) \ + + // @Param: CONNECT_ESC + // @DisplayName: connect to ESC inputs via 4wayIf + // @Description: Allows to connect USB to ESC inputs, thus allowing to configure ESC as on 4-wayIf. Auto-reset. + // @Values: 0:disabled, 1:connect uartA to ESC, 2: connect uartB to ESC, etc + // @User: Advanced + AP_GROUPINFO("CONNECT_ESC", 2, AP_Param_Helper, _connect_esc, 0) \ + + // @Param: PWM_TYPE + // @DisplayName: PWM protocol used + // @Description: Allows to ignore MOT_PWM_TYPE param and set PWM protocol independently + // @Values: 0:use MOT_PWM_TYPE, 1:OneShot 2:OneShot125 3:OneShot42 4:PWM125 + // @User: Advanced + AP_GROUPINFO("PWM_TYPE", 7, AP_Param_Helper, _pwm_type, 0) + + // @Param: RC_INPUT + // @DisplayName: Type of RC input + // @Description: allows to force specified RC input port + // @Values: 0:auto, 1:PPM1 (pin3), 2: PPM2 (pin4) etc + // @User: Advanced + AP_GROUPINFO("RC_INPUT", 9, AP_Param_Helper, _rc_input, 0) + + // @Param: AIBAO_FS + // @DisplayName: Support FailSafe for Walkera Aibao RC + // @Description: Allows to translate of Walkera Aibao RC FailSafe to Ardupilot's failsafe + // @Values: 0: not translate, 1:translate + // @User: Advanced + AP_GROUPINFO("AIBAO_FS", 7, AP_Param_Helper, _aibao_fs, 0) + + // @Param: RC_FS + // @DisplayName: Set time of RC failsafe + // @Description: if none of RC channel changes in that time, then failsafe triggers + // @Values: 0: turned off, >0 - time in seconds. Good values are starting 60s for digital protocols + // @User: Advanced + AP_GROUPINFO("RC_FS", 17, AP_Param_Helper, _rc_fs, 0) + +*/ + +// common parameters for all boards +#define F4LIGHT_HAL_VARINFO \ + AP_GROUPINFO("MOTOR_LAYOUT", 1, AP_Param_Helper, _motor_layout, 0), \ + AP_GROUPINFO("SOFTSERIAL", 2, AP_Param_Helper, _use_softserial, 0), \ + AP_GROUPINFO("UART_SBUS", 3, AP_Param_Helper, _uart_sbus, 0), \ + AP_GROUPINFO("SERVO_MASK", 4, AP_Param_Helper, _servo_mask, 0), \ + AP_GROUPINFO("CONNECT_COM", 5, AP_Param_Helper, _connect_com, 0), \ + AP_GROUPINFO("PWM_TYPE", 7, AP_Param_Helper, _pwm_type, 0), \ + AP_GROUPINFO("CONNECT_ESC", 6, AP_Param_Helper, _connect_esc, 0), \ + AP_GROUPINFO("TIME_OFFSET", 8, AP_Param_Helper, _time_offset, 0), \ + AP_GROUPINFO("CONSOLE_UART", 9, AP_Param_Helper, _console_uart, HAL_CONSOLE_PORT), \ + AP_GROUPINFO("EE_DEFERRED", 10, AP_Param_Helper, _eeprom_deferred, 0), \ + AP_GROUPINFO("RC_INPUT", 11, AP_Param_Helper, _rc_input, 0), \ + AP_GROUPINFO("AIBAO_FS", 12, AP_Param_Helper, _aibao_fs, 0), \ + AP_GROUPINFO("OVERCLOCK", 13, AP_Param_Helper, _overclock, 0), \ + AP_GROUPINFO("CORRECT_GYRO", 14, AP_Param_Helper, _correct_gyro, 0), \ + AP_GROUPINFO("RC_FS", 15, AP_Param_Helper, _rc_fs, 0), \ + AP_GROUPINFO("BOOT_DFU", 16, AP_Param_Helper, _boot_dfu, 0), + + +// parameters +#define F4LIGHT_HAL_PARAMS \ + AP_Int8 _motor_layout; \ + AP_Int8 _uart_sbus; \ + AP_Int8 _use_softserial; \ + AP_Int8 _servo_mask; \ + AP_Int8 _connect_com; \ + AP_Int8 _connect_esc; \ + AP_Int8 _pwm_type; \ + AP_Int8 _time_offset; \ + AP_Int8 _console_uart; \ + AP_Int8 _eeprom_deferred; \ + AP_Int8 _rc_input; \ + AP_Int8 _aibao_fs; \ + AP_Int8 _overclock; \ + AP_Int8 _correct_gyro; \ + AP_Int8 _rc_fs; \ + AP_Int8 _boot_dfu;