Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/AP_Periph/Parameters.cpp
Views: 1798
1#include <AP_HAL/AP_HAL_Boards.h>2#include "AP_Periph.h"34extern const AP_HAL::HAL &hal;56#ifndef HAL_PERIPH_LED_BRIGHT_DEFAULT7#define HAL_PERIPH_LED_BRIGHT_DEFAULT 1008#endif910#ifndef HAL_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT11#define HAL_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT 11520012#endif1314#ifndef AP_PERIPH_RANGEFINDER_PORT_DEFAULT15#define AP_PERIPH_RANGEFINDER_PORT_DEFAULT 316#endif1718#ifndef HAL_PERIPH_GPS_PORT_DEFAULT19#define HAL_PERIPH_GPS_PORT_DEFAULT 320#endif2122#ifndef HAL_PERIPH_ADSB_BAUD_DEFAULT23#define HAL_PERIPH_ADSB_BAUD_DEFAULT 5760024#endif25#ifndef HAL_PERIPH_ADSB_PORT_DEFAULT26#define HAL_PERIPH_ADSB_PORT_DEFAULT 127#endif2829#ifndef AP_PERIPH_MSP_PORT_DEFAULT30#define AP_PERIPH_MSP_PORT_DEFAULT 131#endif3233#ifndef AP_PERIPH_ESC_TELEM_PORT_DEFAULT34#define AP_PERIPH_ESC_TELEM_PORT_DEFAULT -135#endif3637#ifndef AP_PERIPH_ESC_TELEM_RATE_DEFAULT38#define AP_PERIPH_ESC_TELEM_RATE_DEFAULT 5039#endif4041#ifndef AP_PERIPH_BARO_ENABLE_DEFAULT42#define AP_PERIPH_BARO_ENABLE_DEFAULT 143#endif4445#ifndef HAL_PERIPH_BATT_HIDE_MASK_DEFAULT46#define HAL_PERIPH_BATT_HIDE_MASK_DEFAULT 047#endif4849#ifndef AP_PERIPH_EFI_PORT_DEFAULT50#define AP_PERIPH_EFI_PORT_DEFAULT 351#endif5253#ifndef HAL_PERIPH_EFI_BAUDRATE_DEFAULT54#define HAL_PERIPH_EFI_BAUDRATE_DEFAULT 11520055#endif5657#ifndef HAL_DEFAULT_MAV_SYSTEM_ID58#define MAV_SYSTEM_ID 359#else60#define MAV_SYSTEM_ID HAL_DEFAULT_MAV_SYSTEM_ID61#endif6263#ifndef APD_ESC_SERIAL_064#define APD_ESC_SERIAL_0 -165#endif6667#ifndef APD_ESC_SERIAL_168#define APD_ESC_SERIAL_1 -169#endif7071#ifndef AP_PERIPH_PROBE_CONTINUOUS72#define AP_PERIPH_PROBE_CONTINUOUS 073#endif7475/*76* AP_Periph parameter definitions77*78*/7980const AP_Param::Info AP_Periph_FW::var_info[] = {81// @Param: FORMAT_VERSION82// @DisplayName: Eeprom format version number83// @Description: This value is incremented when changes are made to the eeprom format84// @User: Advanced85GSCALAR(format_version, "FORMAT_VERSION", 0),8687// @Param: CAN_NODE88// @DisplayName: DroneCAN node ID used by this node on all networks89// @Description: Value of 0 requests any ID from a DNA server, any other value sets that ID ignoring DNA90// @Range: 0 12791// @User: Advanced92// @RebootRequired: True93GSCALAR(can_node, "CAN_NODE", HAL_CAN_DEFAULT_NODE_ID),9495// @Param: CAN_BAUDRATE96// @DisplayName: Bitrate of CAN interface97// @Description: Bit rate can be set up to from 10000 to 100000098// @Range: 10000 100000099// @User: Advanced100// @RebootRequired: True101GARRAY(can_baudrate, 0, "CAN_BAUDRATE", 1000000),102103#if AP_CAN_SLCAN_ENABLED104// @Param: CAN_SLCAN_CPORT105// @DisplayName: SLCAN Route106// @Description: CAN Interface ID to be routed to SLCAN, 0 means no routing107// @Values: 0:Disabled,1:First interface,2:Second interface108// @User: Standard109// @RebootRequired: True110GSCALAR(can_slcan_cport, "CAN_SLCAN_CPORT", 1),111#endif112113#ifdef HAL_GPIO_PIN_GPIO_CAN1_TERM114// @Param: CAN_TERMINATE115// @DisplayName: Enable CAN software temination in this node116// @Description: Enable CAN software temination in this node117// @Values: 0:Disabled,1:Enabled118// @User: Advanced119// @RebootRequired: True120GARRAY(can_terminate, 0, "CAN_TERMINATE", 0),121#endif122123#if HAL_NUM_CAN_IFACES >= 2124// @Param: CAN_PROTOCOL125// @DisplayName: Enable use of specific protocol to be used on this port126// @Description: Enabling this option starts selected protocol that will use this virtual driver. At least one CAN port must be UAVCAN or else CAN1 gets set to UAVCAN127// @Values: 0:Disabled,1:UAVCAN,4:PiccoloCAN,6:EFI_NWPMU,7:USD1,8:KDECAN128// @User: Advanced129// @RebootRequired: True130GARRAY(can_protocol, 0, "CAN_PROTOCOL", float(AP_CAN::Protocol::DroneCAN)),131132// @Param: CAN2_BAUDRATE133// @CopyFieldsFrom: CAN_BAUDRATE134// @DisplayName: Bitrate of CAN2 interface135GARRAY(can_baudrate, 1, "CAN2_BAUDRATE", 1000000),136137// @Param: CAN2_PROTOCOL138// @CopyFieldsFrom: CAN_PROTOCOL139GARRAY(can_protocol, 1, "CAN2_PROTOCOL", float(AP_CAN::Protocol::DroneCAN)),140141#ifdef HAL_GPIO_PIN_GPIO_CAN2_TERM142// @Param: CAN2_TERMINATE143// @CopyFieldsFrom: CAN_TERMINATE144GARRAY(can_terminate, 1, "CAN2_TERMINATE", 0),145#endif146#endif147148#if HAL_NUM_CAN_IFACES >= 3149// @Param: CAN3_BAUDRATE150// @DisplayName: Bitrate of CAN3 interface151// @CopyFieldsFrom: CAN_BAUDRATE152GARRAY(can_baudrate, 2, "CAN3_BAUDRATE", 1000000),153154// @Param: CAN3_PROTOCOL155// @CopyFieldsFrom: CAN_PROTOCOL156GARRAY(can_protocol, 2, "CAN3_PROTOCOL", float(AP_CAN::Protocol::DroneCAN)),157158#ifdef HAL_GPIO_PIN_GPIO_CAN3_TERM159// @Param: CAN3_TERMINATE160// @CopyFieldsFrom: CAN_TERMINATE161GARRAY(can_terminate, 2, "CAN3_TERMINATE", 0),162#endif163#endif164165#if HAL_CANFD_SUPPORTED166// @Param: CAN_FDMODE167// @DisplayName: Enable CANFD mode168// @Description: Enabling this option sets the CAN bus to be in CANFD mode with BRS.169// @Values: 0:Disabled,1:Enabled170// @User: Advanced171// @RebootRequired: True172GSCALAR(can_fdmode, "CAN_FDMODE", 0),173174// @Param: CAN_FDBAUDRATE175// @DisplayName: Set up bitrate for data section on CAN1176// @Description: This sets the bitrate for the data section of CAN1.177// @Values: 1:1M, 2:2M, 4:4M, 5:5M, 8:8M178// @User: Advanced179// @RebootRequired: True180GARRAY(can_fdbaudrate, 0, "CAN_FDBAUDRATE", HAL_CANFD_SUPPORTED),181182#if HAL_NUM_CAN_IFACES >= 2183// @Param: CAN2_FDBAUDRATE184// @CopyFieldsFrom: CAN_FDBAUDRATE185// @DisplayName: Set up bitrate for data section on CAN2186// @Description: This sets the bitrate for the data section of CAN2.187GARRAY(can_fdbaudrate, 1, "CAN2_FDBAUDRATE", HAL_CANFD_SUPPORTED),188#endif189#endif190191#if !defined(HAL_NO_FLASH_SUPPORT) && !defined(HAL_NO_ROMFS_SUPPORT)192// @Param: FLASH_BOOTLOADER193// @DisplayName: Trigger bootloader update194// @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.195// @Range: 0 1196// @User: Advanced197GSCALAR(flash_bootloader, "FLASH_BOOTLOADER", 0),198#endif199200// @Param: DEBUG201// @DisplayName: Debug202// @Description: Debug203// @Bitmask: 0:Show free stack space, 1:Auto Reboot after 15sec, 2:Enable sending stats204// @User: Advanced205GSCALAR(debug, "DEBUG", 0),206207208// @Param: BRD_SERIAL_NUM209// @DisplayName: Serial number of device210// @Description: Non-zero positive values will be shown on the CAN App Name string211// @Range: 0 2147483648212// @User: Advanced213GSCALAR(serial_number, "BRD_SERIAL_NUM", 0),214215#ifdef HAL_PERIPH_ENABLE_BUZZER_WITHOUT_NOTIFY216// @Param: BUZZER_VOLUME217// @DisplayName: Buzzer volume218// @Description: Control the volume of the buzzer219// @Range: 0 100220// @Units: %221// @Increment: 1222// @User: Advanced223GSCALAR(buzz_volume, "BUZZER_VOLUME", 100),224#endif225226#ifdef HAL_PERIPH_ENABLE_GPS227// GPS driver228// @Group: GPS229// @Path: ../libraries/AP_GPS/AP_GPS.cpp230GOBJECT(gps, "GPS", AP_GPS),231232// @Param: GPS_PORT233// @DisplayName: GPS Serial Port234// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to GPS.235// @Range: 0 10236// @Increment: 1237// @User: Advanced238// @RebootRequired: True239GSCALAR(gps_port, "GPS_PORT", HAL_PERIPH_GPS_PORT_DEFAULT),240241#if GPS_MOVING_BASELINE242// @Param: MB_CAN_PORT243// @DisplayName: Moving Baseline CAN Port option244// @Description: Autoselect dedicated CAN port on which moving baseline data will be transmitted.245// @Values: 0:Sends moving baseline data on all ports,1:auto select remaining port for transmitting Moving baseline Data246// @User: Advanced247// @RebootRequired: True248GSCALAR(gps_mb_only_can_port, "GPS_MB_ONLY_PORT", 0),249#endif250#endif251252#ifdef HAL_PERIPH_ENABLE_BATTERY253// @Group: BATT254// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp255GOBJECT(battery_lib, "BATT", AP_BattMonitor),256257// @Param: BATT_HIDE_MASK258// @DisplayName: Battery hide mask259// @Description: Instance mask of local battery index(es) to prevent transmitting their status over CAN. This is useful for hiding a "battery" instance that is used locally in the peripheral but don't want them to be treated as a battery source(s) to the autopilot. For example, an AP_Periph battery monitor with multiple batteries that monitors each locally for diagnostic or other purposes, but only reports as a single SUM battery monitor to the autopilot.260// @Bitmask: 0:BATT, 1:BATT2, 2:BATT3, 3:BATT4, 4:BATT5, 5:BATT6, 6:BATT7, 7:BATT8, 8:BATT9, 9:BATTA, 10:BATTB, 11:BATTC, 12:BATTD, 13:BATTE, 14:BATTF, 15:BATTG261// @User: Advanced262GSCALAR(battery_hide_mask, "BATT_HIDE_MASK", HAL_PERIPH_BATT_HIDE_MASK_DEFAULT),263#endif264265#ifdef HAL_PERIPH_ENABLE_MAG266// @Group: COMPASS_267// @Path: ../libraries/AP_Compass/AP_Compass.cpp268GOBJECT(compass, "COMPASS_", Compass),269#endif270271#ifdef HAL_PERIPH_ENABLE_BARO272// Baro driver273// @Group: BARO274// @Path: ../libraries/AP_Baro/AP_Baro.cpp275GOBJECT(baro, "BARO", AP_Baro),276277// @Param: BARO_ENABLE278// @DisplayName: Barometer Enable279// @Description: Barometer Enable280// @Values: 0:Disabled, 1:Enabled281// @User: Standard282GSCALAR(baro_enable, "BARO_ENABLE", AP_PERIPH_BARO_ENABLE_DEFAULT),283#endif284285#ifdef AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY286// @Param: LED_BRIGHTNESS287// @DisplayName: LED Brightness288// @Description: Select the RGB LED brightness level.289// @Range: 0 100290// @Units: %291// @Increment: 1292// @User: Standard293GSCALAR(led_brightness, "LED_BRIGHTNESS", HAL_PERIPH_LED_BRIGHT_DEFAULT),294#endif295296#ifdef HAL_PERIPH_ENABLE_AIRSPEED297// Airspeed driver298// @Group: ARSPD299// @Path: ../libraries/AP_Airspeed/AP_Airspeed.cpp300GOBJECT(airspeed, "ARSPD", AP_Airspeed),301#endif302303#ifdef HAL_PERIPH_ENABLE_RANGEFINDER304// @Param: RNGFND_BAUDRATE305// @DisplayName: Rangefinder serial baudrate306// @Description: Rangefinder serial baudrate.307// @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:1500000308// @Increment: 1309// @User: Standard310// @RebootRequired: True311GARRAY(rangefinder_baud, 0, "RNGFND_BAUDRATE", HAL_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT),312313// @Param: RNGFND_PORT314// @DisplayName: Rangefinder Serial Port315// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to Rangefinder.316// @Range: 0 10317// @Increment: 1318// @User: Advanced319// @RebootRequired: True320GARRAY(rangefinder_port, 0, "RNGFND_PORT", AP_PERIPH_RANGEFINDER_PORT_DEFAULT),321322#if RANGEFINDER_MAX_INSTANCES > 1323// @Param: RNGFND2_BAUDRATE324// @DisplayName: Rangefinder serial baudrate325// @Description: Rangefinder serial baudrate.326// @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:1500000327// @Increment: 1328// @User: Standard329// @RebootRequired: True330GARRAY(rangefinder_baud, 1, "RNGFND2_BAUDRATE", HAL_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT),331332// @Param: RNGFND2_PORT333// @DisplayName: Rangefinder Serial Port334// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to Rangefinder.335// @Range: 0 10336// @Increment: 1337// @User: Advanced338// @RebootRequired: True339GARRAY(rangefinder_port, 1, "RNGFND2_PORT", -1),340#endif341342// @Param: RNGFND_MAX_RATE343// @DisplayName: Rangefinder max rate344// @Description: This is the maximum rate we send rangefinder data in Hz. Zero means no limit345// @Units: Hz346// @Range: 0 200347// @Increment: 1348// @User: Advanced349GSCALAR(rangefinder_max_rate, "RNGFND_MAX_RATE", 50),350351// Rangefinder driver352// @Group: RNGFND353// @Path: ../libraries/AP_RangeFinder/AP_RangeFinder.cpp354GOBJECT(rangefinder, "RNGFND", RangeFinder),355#endif356357#ifdef HAL_PERIPH_ENABLE_ADSB358// @Param: ADSB_BAUDRATE359// @DisplayName: ADSB serial baudrate360// @Description: ADSB serial baudrate.361// @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:1500000362// @Increment: 1363// @User: Standard364// @RebootRequired: True365GSCALAR(adsb_baudrate, "ADSB_BAUDRATE", HAL_PERIPH_ADSB_BAUD_DEFAULT),366367// @Param: ADSB_PORT368// @DisplayName: ADSB Serial Port369// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to ADSB.370// @Range: 0 10371// @Increment: 1372// @User: Advanced373// @RebootRequired: True374GSCALAR(adsb_port, "ADSB_PORT", HAL_PERIPH_ADSB_PORT_DEFAULT),375#endif376377#ifdef HAL_PERIPH_ENABLE_PWM_HARDPOINT378// @Param: HARDPOINT_ID379// @DisplayName: Hardpoint ID380// @Description: Hardpoint ID381// @User: Advanced382GSCALAR(hardpoint_id, "HARDPOINT_ID", HAL_PWM_HARDPOINT_ID_DEFAULT),383384// @Param: HARDPOINT_RATE385// @DisplayName: Hardpoint PWM rate386// @Description: Hardpoint PWM rate387// @Range: 10 100388// @Units: Hz389// @Increment: 1390// @User: Advanced391GSCALAR(hardpoint_rate, "HARDPOINT_RATE", 100),392#endif393394#if defined(HAL_PERIPH_ENABLE_HWESC) || defined(HAL_PERIPH_ENABLE_ESC_APD)395// @Param: ESC_NUMBER396// @DisplayName: ESC number397// @Description: This is the ESC number to report as in UAVCAN ESC telemetry feedback packets.398// @Increment: 1399// @User: Advanced400GARRAY(esc_number, 0, "ESC_NUMBER", 0),401#endif402403#ifdef HAL_PERIPH_ENABLE_RC_OUT404// Servo driver405// @Group: OUT406// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp407GOBJECT(servo_channels, "OUT", SRV_Channels),408409// @Param: ESC_RATE410// @DisplayName: ESC Update Rate411// @Description: Rate in Hz that ESC PWM outputs (function is MotorN) will update at412// @Units: Hz413// @Range: 50 400414// @Increment: 1415// @User: Advanced416GSCALAR(esc_rate, "ESC_RATE", 400), // effective Copter and QuadPlane default after clamping417418// @Param: ESC_PWM_TYPE419// @DisplayName: Output PWM type420// @Description: This selects the output PWM type, allowing for normal PWM continuous output, OneShot, brushed or DShot motor output421// @Values: 1:Normal,2:OneShot,3:OneShot125,4:Brushed,5:DShot150,6:DShot300,7:DShot600,8:DShot1200422// @User: Advanced423// @RebootRequired: True424GSCALAR(esc_pwm_type, "ESC_PWM_TYPE", 0),425426// @Param: ESC_CMD_TIMO427// @DisplayName: ESC Command Timeout428// @Description: This is the duration (ms) with which to hold the last driven ESC command before timing out and zeroing the ESC outputs. To disable zeroing of outputs in event of CAN loss, use 0. Use values greater than the expected duration between two CAN frames to ensure Periph is not starved of ESC Raw Commands.429// @Range: 0 10000430// @Units: ms431// @User: Advanced432GSCALAR(esc_command_timeout_ms, "ESC_CMD_TIMO", 200),433434#if HAL_WITH_ESC_TELEM && !HAL_GCS_ENABLED435// @Param: ESC_TELEM_PORT436// @DisplayName: ESC Telemetry Serial Port437// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to ESC Telemetry438// @Range: 0 10439// @Increment: 1440// @User: Advanced441// @RebootRequired: True442GSCALAR(esc_telem_port, "ESC_TELEM_PORT", AP_PERIPH_ESC_TELEM_PORT_DEFAULT),443#endif444445#if HAL_WITH_ESC_TELEM446// @Param: ESC_TELEM_RATE447// @DisplayName: ESC Telemetry update rate448// @Description: This is the rate at which ESC Telemetry will be sent across the CAN bus449// @Range: 0 1000450// @Increment: 1451// @User: Advanced452// @RebootRequired: True453GSCALAR(esc_telem_rate, "ESC_TELEM_RATE", AP_PERIPH_ESC_TELEM_RATE_DEFAULT),454#endif455#endif456457#if AP_TEMPERATURE_SENSOR_ENABLED458// @Group: TEMP459// @Path: ../libraries/AP_TemperatureSensor/AP_TemperatureSensor.cpp460GOBJECT(temperature_sensor, "TEMP", AP_TemperatureSensor),461#endif462463#ifdef HAL_PERIPH_ENABLE_MSP464// @Param: MSP_PORT465// @DisplayName: MSP Serial Port466// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to MSP467// @Range: 0 10468// @Increment: 1469// @User: Advanced470// @RebootRequired: True471GSCALAR(msp_port, "MSP_PORT", AP_PERIPH_MSP_PORT_DEFAULT),472#endif473474#ifdef HAL_PERIPH_ENABLE_NOTIFY475// @Group: NTF_476// @Path: ../libraries/AP_Notify/AP_Notify.cpp477GOBJECT(notify, "NTF_", AP_Notify),478#endif479480#if HAL_LOGGING_ENABLED481// @Group: LOG482// @Path: ../libraries/AP_Logger/AP_Logger.cpp483GOBJECT(logger, "LOG", AP_Logger),484485// @Param: LOG_BITMASK486// @DisplayName: Log bitmask487// @Description: 4 byte bitmap of log types to enable488// @Bitmask: 2:GPS489// @User: Standard490GSCALAR(log_bitmask, "LOG_BITMASK", 4),491#endif492493#if HAL_GCS_ENABLED494// @Param: SYSID_THISMAV495// @DisplayName: MAVLink system ID of this vehicle496// @Description: Allows setting an individual system id for this vehicle to distinguish it from others on the same network497// @Range: 1 255498// @User: Advanced499GSCALAR(sysid_this_mav, "SYSID_THISMAV", MAV_SYSTEM_ID),500#endif501502#if HAL_GCS_ENABLED || defined(HAL_PERIPH_SHOW_SERIAL_MANAGER_PARAMS)503// @Group: SERIAL504// @Path: ../libraries/AP_SerialManager/AP_SerialManager.cpp505GOBJECT(serial_manager, "SERIAL", AP_SerialManager),506#endif507508#if AP_SCRIPTING_ENABLED509// @Group: SCR_510// @Path: ../libraries/AP_Scripting/AP_Scripting.cpp511GOBJECT(scripting, "SCR_", AP_Scripting),512#endif513514#if AP_STATS_ENABLED515// @Group: Node516// @Path: ../libraries/AP_Stats/AP_Stats.cpp517GOBJECT(node_stats, "STAT", AP_Stats),518#endif519520#ifdef HAL_PERIPH_ENABLE_EFI521// @Param: EFI_BAUDRATE522// @DisplayName: EFI serial baudrate523// @Description: EFI serial baudrate.524// @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:1500000525// @Increment: 1526// @User: Standard527// @RebootRequired: True528GSCALAR(efi_baudrate, "EFI_BAUDRATE", HAL_PERIPH_EFI_BAUDRATE_DEFAULT),529530// @Param: EFI_PORT531// @DisplayName: EFI Serial Port532// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to EFI.533// @Range: 0 10534// @Increment: 1535// @User: Advanced536// @RebootRequired: True537GSCALAR(efi_port, "EFI_PORT", AP_PERIPH_EFI_PORT_DEFAULT),538539// EFI driver540// @Group: EFI541// @Path: ../libraries/AP_EFI/AP_EFI.cpp542GOBJECT(efi, "EFI", AP_EFI),543#endif544545#ifdef HAL_PERIPH_ENABLE_PROXIMITY546// @Param: PRX_BAUDRATE547// @DisplayName: Proximity Sensor serial baudrate548// @Description: Proximity Sensor serial baudrate.549// @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:1500000550// @Increment: 1551// @User: Standard552// @RebootRequired: True553GSCALAR(proximity_baud, "PRX_BAUDRATE", HAL_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT),554555// @Param: PRX_PORT556// @DisplayName: Proximity Sensor Serial Port557// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to Proximity Sensor.558// @Range: 0 10559// @Increment: 1560// @User: Advanced561// @RebootRequired: True562GSCALAR(proximity_port, "PRX_PORT", AP_PERIPH_RANGEFINDER_PORT_DEFAULT),563564// @Param: PRX_MAX_RATE565// @DisplayName: Proximity Sensor max rate566// @Description: This is the maximum rate we send Proximity Sensor data in Hz. Zero means no limit567// @Units: Hz568// @Range: 0 200569// @Increment: 1570// @User: Advanced571GSCALAR(proximity_max_rate, "PRX_MAX_RATE", 50),572573// Proximity driver574// @Group: PRX575// @Path: ../libraries/AP_Proximity/AP_Proximity.cpp576GOBJECT(proximity, "PRX", AP_Proximity),577#endif // HAL_PERIPH_ENABLE_PROXIMITY578579#if HAL_NMEA_OUTPUT_ENABLED580// @Group: NMEA_581// @Path: ../libraries/AP_NMEA_Output/AP_NMEA_Output.cpp582GOBJECT(nmea, "NMEA_", AP_NMEA_Output),583#endif584585#if AP_KDECAN_ENABLED586// @Group: KDE_587// @Path: ../libraries/AP_KDECAN/AP_KDECAN.cpp588GOBJECT(kdecan, "KDE_", AP_KDECAN),589#endif590591#if defined(HAL_PERIPH_ENABLE_ESC_APD)592GARRAY(pole_count, 0, "ESC_NUM_POLES", 22),593#endif594595#if defined(HAL_PERIPH_ENABLE_ESC_APD)596// @Param: ESC_APD_SERIAL_1597// @DisplayName: ESC APD Serial 1598// @Description: Which serial port to use for APD ESC data599// @Range: 0 6600// @Increment: 1601// @User: Advanced602// @RebootRequired: True603GARRAY(esc_serial_port, 0, "ESC_APD_SERIAL_1", APD_ESC_SERIAL_0),604605#if APD_ESC_INSTANCES > 1606GARRAY(esc_number, 1, "ESC_NUMBER2", 1),607608GARRAY(pole_count, 1, "ESC_NUM_POLES2", 22),609610// @Param: ESC_APD_SERIAL_2611// @DisplayName: ESC APD Serial 2612// @Description: Which serial port to use for APD ESC data613// @Range: 0 6614// @Increment: 1615// @User: Advanced616// @RebootRequired: True617GARRAY(esc_serial_port, 1, "ESC_APD_SERIAL_2", APD_ESC_SERIAL_1),618#endif619#endif620621#ifdef HAL_PERIPH_ENABLE_NETWORKING622// @Group: NET_623// @Path: networking.cpp624GOBJECT(networking_periph, "NET_", Networking_Periph),625#endif626627#ifdef HAL_PERIPH_ENABLE_RPM628// @Group: RPM629// @Path: ../libraries/AP_RPM/AP_RPM.cpp630GOBJECT(rpm_sensor, "RPM", AP_RPM),631#endif632633#ifdef HAL_PERIPH_ENABLE_RCIN634// @Group: RC635// @Path: rc_in.cpp636GOBJECT(g_rcin, "RC", Parameters_RCIN),637#endif638639#ifdef HAL_PERIPH_ENABLE_BATTERY_BALANCE640// @Group: BAL641// @Path: batt_balance.cpp642GOBJECT(battery_balance, "BAL", BattBalance),643#endif644645#ifdef HAL_PERIPH_ENABLE_SERIAL_OPTIONS646// @Group: UART647// @Path: serial_options.cpp648GOBJECT(serial_options, "UART", SerialOptions),649#endif650651// NOTE: sim parameters should go last652#if AP_SIM_ENABLED653// @Group: SIM_654// @Path: ../libraries/SITL/SITL.cpp655GOBJECT(sitl, "SIM_", SITL::SIM),656657#if AP_AHRS_ENABLED658// @Group: AHRS_659// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp660GOBJECT(ahrs, "AHRS_", AP_AHRS),661#endif662#endif // AP_SIM_ENABLED663664#if HAL_PERIPH_CAN_MIRROR665// @Param: CAN_MIRROR_PORTS666// @DisplayName: CAN ports to mirror traffic between667// @Description: Any set ports will participate in blindly mirroring traffic from one port to the other. It is the users responsibility to ensure that no loops exist that cause traffic to be infinitly repeated, and both ports must be running the same baud rates.668// @Bitmask: 0:CAN1, 1:CAN2, 2:CAN3669// @User: Advanced670GSCALAR(can_mirror_ports, "CAN_MIRROR_PORTS", 0),671#endif // HAL_PERIPH_CAN_MIRROR672673#ifdef HAL_PERIPH_ENABLE_RTC674// @Group: RTC675// @Path: ../libraries/AP_RTC/AP_RTC.cpp676GOBJECT(rtc, "RTC", AP_RTC),677#endif678679#ifdef HAL_PERIPH_ENABLE_RELAY680// @Group: RELAY681// @Path: ../libraries/AP_Relay/AP_Relay.cpp682GOBJECT(relay, "RELAY", AP_Relay),683#endif684685#ifdef HAL_PERIPH_ENABLE_DEVICE_TEMPERATURE686// @Param: TEMP_MSG_RATE687// @DisplayName: Temperature sensor message rate688// @Description: This is the rate Temperature sensor data is sent in Hz. Zero means no send. Each sensor with source DroneCAN is sent in turn.689// @Units: Hz690// @Range: 0 200691// @Increment: 1692// @User: Standard693GSCALAR(temperature_msg_rate, "TEMP_MSG_RATE", 0),694#endif695696// @Param: OPTIONS697// @DisplayName: AP Periph Options698// @Description: Bitmask of AP Periph Options699// @Bitmask: 0: Enable continuous sensor probe700// @User: Standard701GSCALAR(options, "OPTIONS", AP_PERIPH_PROBE_CONTINUOUS),702703#ifdef HAL_PERIPH_ENABLE_RPM_STREAM704// @Param: RPM_MSG_RATE705// @DisplayName: RPM sensor message rate706// @Description: This is the rate RPM sensor data is sent in Hz. Zero means no send. Each sensor with a set ID is sent in turn.707// @Units: Hz708// @Range: 0 200709// @Increment: 1710// @User: Standard711GSCALAR(rpm_msg_rate, "RPM_MSG_RATE", 0),712#endif713714#if AP_EXTENDED_ESC_TELEM_ENABLED && HAL_WITH_ESC_TELEM715// @Param: ESC_EXT_TLM_RATE716// @DisplayName: ESC Extended telemetry message rate717// @Description: This is the rate at which extended ESC Telemetry will be sent across the CAN bus for each ESC718// @Units: Hz719// @Range: 0 50720// @Increment: 1721// @User: Advanced722GSCALAR(esc_extended_telem_rate, "ESC_EXT_TLM_RATE", AP_PERIPH_ESC_TELEM_RATE_DEFAULT / 10),723#endif724725726#ifdef HAL_PERIPH_ENABLE_IMU727// @Param: IMU_SAMPLE_RATE728// @DisplayName: IMU Sample Rate729// @Description: IMU Sample Rate730// @Range: 0 1000731// @User: Standard732GSCALAR(imu_sample_rate, "INS_SAMPLE_RATE", 0),733734// @Group: INS735// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp736GOBJECT(imu, "INS", AP_InertialSensor),737#endif738739AP_VAREND740};741742743void AP_Periph_FW::load_parameters(void)744{745AP_Param::setup_sketch_defaults();746747AP_Param::check_var_info();748749if (!g.format_version.load() ||750g.format_version != Parameters::k_format_version) {751// erase all parameters752StorageManager::erase();753AP_Param::erase_all();754755// save the current format version756g.format_version.set_and_save(Parameters::k_format_version);757}758g.format_version.set_default(Parameters::k_format_version);759760// Load all auto-loaded EEPROM variables761AP_Param::load_all();762}763764765