AP_Periph: populate the param meta data for the wiki

This commit is contained in:
Tom Pittenger 2021-04-18 15:29:15 -07:00 committed by Tom Pittenger
parent 93a13bbf0e
commit e0cfac902d

View File

@ -47,22 +47,53 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
// @User: Advanced
GSCALAR(format_version, "FORMAT_VERSION", 0),
// can node number, 0 for dynamic node allocation
// @Param: CAN_NODE
// @DisplayName: UAVCAN node that is used for this network
// @Description: UAVCAN node should be set implicitly or 0 for dynamic node allocation
// @Range: 0 250
// @User: Advanced
// @RebootRequired: True
GSCALAR(can_node, "CAN_NODE", HAL_CAN_DEFAULT_NODE_ID),
// can node baudrate
// @Param: CAN_BAUDRATE
// @DisplayName: Bitrate of CAN interface
// @Description: Bit rate can be set up to from 10000 to 1000000
// @Range: 10000 1000000
// @User: Advanced
// @RebootRequired: True
GSCALAR(can_baudrate, "CAN_BAUDRATE", 1000000),
#if !defined(HAL_NO_FLASH_SUPPORT) && !defined(HAL_NO_ROMFS_SUPPORT)
// trigger bootloader flash
// @Param: FLASH_BOOTLOADER
// @DisplayName: Trigger bootloader update
// @Description: DANGER! When enabled, the App will perform a bootloader update by copying the embedded bootloader over the existing bootloader. This may take a few seconds to perform and should only be done if you know what you're doing.
// @Range: 0 1
// @User: Advanced
GSCALAR(flash_bootloader, "FLASH_BOOTLOADER", 0),
#endif
// @Param: DEBUG
// @DisplayName: Debug
// @Description: Debug
// @Values: 0:Disabled, 1:Show free stack space
// @User: Advanced
GSCALAR(debug, "DEBUG", 0),
// @Param: BRD_SERIAL_NUM
// @DisplayName: Serial number of device
// @Description: Non-zero positive values will be shown on the CAN App Name string
// @Range: 0 2147483648
// @User: Advanced
GSCALAR(serial_number, "BRD_SERIAL_NUM", 0),
#ifdef HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY
// @Param: BUZZ_VOLUME
// @DisplayName: Buzzer volume
// @Description: Control the volume of the buzzer
// @Range: 0 100
// @Units: %
// @Increment: 1
// @User: Advanced
GSCALAR(buzz_volume, "BUZZER_VOLUME", 100),
#endif
@ -99,10 +130,23 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
// @Group: BARO
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
GOBJECT(baro, "BARO", AP_Baro),
// @Param: BARO_ENABLE
// @DisplayName: Barometer Enable
// @Description: Barometer Enable
// @Values: 0:Disabled, 1:Enabled
// @User: Standard
GSCALAR(baro_enable, "BARO_ENABLE", 1),
#endif
#ifdef AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY
// @Param: LED_BRIGHTNESS
// @DisplayName: LED Brightness
// @Description: Select the RGB LED brightness level.
// @Range: 0 100
// @Units: %
// @Increment: 1
// @User: Standard
GSCALAR(led_brightness, "LED_BRIGHTNESS", HAL_PERIPH_LED_BRIGHT_DEFAULT),
#endif
@ -114,7 +158,23 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
#endif
#ifdef HAL_PERIPH_ENABLE_RANGEFINDER
// @Param: RNGFND_BAUDRATE
// @DisplayName: Rangefinder serial baudrate
// @Description: Rangefinder serial baudrate.
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,230:230400,256:256000,460:460800,500:500000,921:921600,1500:1500000
// @Units: %
// @Increment: 1
// @User: Standard
// @RebootRequired: True
GSCALAR(rangefinder_baud, "RNGFND_BAUDRATE", HAL_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT),
// @Param: RNGFND_PORT
// @DisplayName: Rangefinder Serial Port
// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to Rangefinder.
// @Range: 0 10
// @Increment: 1
// @User: Advanced
// @RebootRequired: True
GSCALAR(rangefinder_port, "RNGFND_PORT", HAL_PERIPH_RANGEFINDER_PORT_DEFAULT),
// Rangefinder driver
@ -124,16 +184,49 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
#endif
#ifdef HAL_PERIPH_ENABLE_ADSB
// @Param: ADSB_BAUDRATE
// @DisplayName: ADSB serial baudrate
// @Description: ADSB serial baudrate.
// @Values: 1:1200,2:2400,4:4800,9:9600,19:19200,38:38400,57:57600,111:111100,115:115200,230:230400,256:256000,460:460800,500:500000,921:921600,1500:1500000
// @Units: %
// @Increment: 1
// @User: Standard
// @RebootRequired: True
GSCALAR(adsb_baudrate, "ADSB_BAUDRATE", HAL_PERIPH_ADSB_BAUD_DEFAULT),
// @Param: ADSB_PORT
// @DisplayName: ADSB Serial Port
// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to ADSB.
// @Range: 0 10
// @Increment: 1
// @User: Advanced
// @RebootRequired: True
GSCALAR(adsb_port, "ADSB_PORT", HAL_PERIPH_ADSB_PORT_DEFAULT),
#endif
#ifdef HAL_PERIPH_ENABLE_PWM_HARDPOINT
// @Param: HARDPOINT_ID
// @DisplayName: Hardpoint ID
// @Description: Hardpoint ID
// @User: Advanced
GSCALAR(hardpoint_id, "HARDPOINT_ID", HAL_PWM_HARDPOINT_ID_DEFAULT),
// @Param: HARDPOINT_RATE
// @DisplayName: Hardpoint PWM rate
// @Description: Hardpoint PWM rate
// @Range: 10 100
// @Units: Hz
// @Increment: 1
// @User: Advanced
GSCALAR(hardpoint_rate, "HARDPOINT_RATE", 100),
#endif
#ifdef HAL_PERIPH_ENABLE_HWESC
// @Param: ESC_NUMBER
// @DisplayName: ESC number
// @Description: This is the ESC number to report as in UAVCAN ESC telemetry feedback packets.
// @Increment: 1
// @User: Advanced
GSCALAR(esc_number, "ESC_NUMBER", 0),
#endif
@ -143,11 +236,23 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp
GOBJECT(servo_channels, "OUT", SRV_Channels),
// PWM type for ESCs (to allow for DShot and OneShot)
// @Param: ESC_PWM_TYPE
// @DisplayName: Output PWM type
// @Description: This selects the output PWM type, allowing for normal PWM continuous output, OneShot, brushed or DShot motor output
// @Values: 0:Normal,1:OneShot,2:OneShot125,3:Brushed,4:DShot150,5:DShot300,6:DShot600,7:DShot1200
// @User: Advanced
// @RebootRequired: True
GSCALAR(esc_pwm_type, "ESC_PWM_TYPE", 0),
#endif
#ifdef HAL_PERIPH_ENABLE_MSP
// @Param: MSP_PORT
// @DisplayName: MSP Serial Port
// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to MSP
// @Range: 0 10
// @Increment: 1
// @User: Advanced
// @RebootRequired: True
GSCALAR(msp_port, "MSP_PORT", AP_PERIPH_MSP_PORT_DEFAULT),
#endif