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 termination in this node116// @Description: Enable CAN software termination 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#if AP_PERIPH_BUZZER_WITHOUT_NOTIFY_ENABLED216// @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#if AP_PERIPH_GPS_ENABLED227// 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#if AP_PERIPH_BATTERY_ENABLED253// @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#if AP_PERIPH_MAG_ENABLED266// @Group: COMPASS_267// @Path: ../libraries/AP_Compass/AP_Compass.cpp268GOBJECT(compass, "COMPASS_", Compass),269#endif270271#if AP_PERIPH_BARO_ENABLED272// 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#if 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#if AP_PERIPH_AIRSPEED_ENABLED297// Airspeed driver298// @Group: ARSPD299// @Path: ../libraries/AP_Airspeed/AP_Airspeed.cpp300GOBJECT(airspeed, "ARSPD", AP_Airspeed),301#endif302303#if AP_PERIPH_RANGEFINDER_ENABLED304// @Param: RNGFND_BAUDRATE305// @DisplayName: Rangefinder serial baudrate306// @Description: Rangefinder serial baudrate.307// @Values: 1200:1200,2400:2400,4800:4800,9600:9600,19200:19200,38400:38400,57600:57600,111100:111100,115200:115200,230400:230400,256000:256000,460800:460800,500000:500000,921600:921600,1500000:1500000308// @Range: 1200 20000000309// @Increment: 1310// @User: Standard311// @RebootRequired: True312GARRAY(rangefinder_baud, 0, "RNGFND_BAUDRATE", HAL_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT),313314// @Param: RNGFND_PORT315// @DisplayName: Rangefinder Serial Port316// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to Rangefinder.317// @Range: 0 10318// @Increment: 1319// @User: Advanced320// @RebootRequired: True321GARRAY(rangefinder_port, 0, "RNGFND_PORT", AP_PERIPH_RANGEFINDER_PORT_DEFAULT),322323#if RANGEFINDER_MAX_INSTANCES > 1324// @Param: RNGFND2_BAUDRATE325// @CopyFieldsFrom: RNGFND_BAUDRATE326GARRAY(rangefinder_baud, 1, "RNGFND2_BAUDRATE", HAL_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT),327328// @Param: RNGFND2_PORT329// @DisplayName: Rangefinder Serial Port330// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to Rangefinder.331// @Range: 0 10332// @Increment: 1333// @User: Advanced334// @RebootRequired: True335GARRAY(rangefinder_port, 1, "RNGFND2_PORT", -1),336#endif337338// @Param: RNGFND_MAX_RATE339// @DisplayName: Rangefinder max rate340// @Description: This is the maximum rate we send rangefinder data in Hz. Zero means no limit341// @Units: Hz342// @Range: 0 200343// @Increment: 1344// @User: Advanced345GSCALAR(rangefinder_max_rate, "RNGFND_MAX_RATE", 50),346347// Rangefinder driver348// @Group: RNGFND349// @Path: ../libraries/AP_RangeFinder/AP_RangeFinder.cpp350GOBJECT(rangefinder, "RNGFND", RangeFinder),351#endif352353#if AP_PERIPH_ADSB_ENABLED354// @Param: ADSB_BAUDRATE355// @CopyFieldsFrom: RNGFND_BAUDRATE356// @DisplayName: ADSB serial baudrate357// @Description: ADSB serial baudrate.358GSCALAR(adsb_baudrate, "ADSB_BAUDRATE", HAL_PERIPH_ADSB_BAUD_DEFAULT),359360// @Param: ADSB_PORT361// @DisplayName: ADSB Serial Port362// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to ADSB.363// @Range: 0 10364// @Increment: 1365// @User: Advanced366// @RebootRequired: True367GSCALAR(adsb_port, "ADSB_PORT", HAL_PERIPH_ADSB_PORT_DEFAULT),368#endif369370#if AP_PERIPH_PWM_HARDPOINT_ENABLED371// @Param: HARDPOINT_ID372// @DisplayName: Hardpoint ID373// @Description: Hardpoint ID374// @User: Advanced375GSCALAR(hardpoint_id, "HARDPOINT_ID", HAL_PWM_HARDPOINT_ID_DEFAULT),376377// @Param: HARDPOINT_RATE378// @DisplayName: Hardpoint PWM rate379// @Description: Hardpoint PWM rate380// @Range: 10 100381// @Units: Hz382// @Increment: 1383// @User: Advanced384GSCALAR(hardpoint_rate, "HARDPOINT_RATE", 100),385#endif386387#if AP_PERIPH_HOBBYWING_ESC_ENABLED || AP_PERIPH_ESC_APD_ENABLED388// @Param: ESC_NUMBER389// @DisplayName: ESC number390// @Description: This is the ESC number to report as in UAVCAN ESC telemetry feedback packets.391// @Increment: 1392// @User: Advanced393GARRAY(esc_number, 0, "ESC_NUMBER", 0),394#endif395396#if AP_PERIPH_RC_OUT_ENABLED397// Servo driver398// @Group: OUT399// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp400GOBJECT(servo_channels, "OUT", SRV_Channels),401402// @Param: ESC_RATE403// @DisplayName: ESC Update Rate404// @Description: Rate in Hz that ESC PWM outputs (function is MotorN) will update at405// @Units: Hz406// @Range: 50 400407// @Increment: 1408// @User: Advanced409GSCALAR(esc_rate, "ESC_RATE", 400), // effective Copter and QuadPlane default after clamping410411// @Param: ESC_PWM_TYPE412// @DisplayName: Output PWM type413// @Description: This selects the output PWM type, allowing for normal PWM continuous output, OneShot, brushed or DShot motor output414// @Values: 1:Normal,2:OneShot,3:OneShot125,4:Brushed,5:DShot150,6:DShot300,7:DShot600,8:DShot1200415// @User: Advanced416// @RebootRequired: True417GSCALAR(esc_pwm_type, "ESC_PWM_TYPE", 0),418419// @Param: ESC_CMD_TIMO420// @DisplayName: ESC Command Timeout421// @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.422// @Range: 0 10000423// @Units: ms424// @User: Advanced425GSCALAR(esc_command_timeout_ms, "ESC_CMD_TIMO", 200),426427#if HAL_WITH_ESC_TELEM && !HAL_GCS_ENABLED428// @Param: ESC_TELEM_PORT429// @DisplayName: ESC Telemetry Serial Port430// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to ESC Telemetry431// @Range: 0 10432// @Increment: 1433// @User: Advanced434// @RebootRequired: True435GSCALAR(esc_telem_port, "ESC_TELEM_PORT", AP_PERIPH_ESC_TELEM_PORT_DEFAULT),436#endif437438#if HAL_WITH_ESC_TELEM439// @Param: ESC_TELEM_RATE440// @DisplayName: ESC Telemetry update rate441// @Description: This is the rate at which ESC Telemetry will be sent across the CAN bus442// @Range: 0 1000443// @Increment: 1444// @User: Advanced445// @RebootRequired: True446GSCALAR(esc_telem_rate, "ESC_TELEM_RATE", AP_PERIPH_ESC_TELEM_RATE_DEFAULT),447#endif448#endif449450#if AP_TEMPERATURE_SENSOR_ENABLED451// @Group: TEMP452// @Path: ../libraries/AP_TemperatureSensor/AP_TemperatureSensor.cpp453GOBJECT(temperature_sensor, "TEMP", AP_TemperatureSensor),454#endif455456#if AP_PERIPH_MSP_ENABLED457// @Param: MSP_PORT458// @DisplayName: MSP Serial Port459// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to MSP460// @Range: 0 10461// @Increment: 1462// @User: Advanced463// @RebootRequired: True464GSCALAR(msp_port, "MSP_PORT", AP_PERIPH_MSP_PORT_DEFAULT),465#endif466467#if AP_PERIPH_NOTIFY_ENABLED468// @Group: NTF_469// @Path: ../libraries/AP_Notify/AP_Notify.cpp470GOBJECT(notify, "NTF_", AP_Notify),471#endif472473#if HAL_LOGGING_ENABLED474// @Group: LOG475// @Path: ../libraries/AP_Logger/AP_Logger.cpp476GOBJECT(logger, "LOG", AP_Logger),477478// @Param: LOG_BITMASK479// @DisplayName: Log bitmask480// @Description: 4 byte bitmap of log types to enable481// @Bitmask: 2:GPS482// @User: Standard483GSCALAR(log_bitmask, "LOG_BITMASK", 4),484#endif485486// SYSID_THISMAV was here487488#if HAL_GCS_ENABLED || defined(HAL_PERIPH_SHOW_SERIAL_MANAGER_PARAMS)489// @Group: SERIAL490// @Path: ../libraries/AP_SerialManager/AP_SerialManager.cpp491GOBJECT(serial_manager, "SERIAL", AP_SerialManager),492#endif493494#if AP_SCRIPTING_ENABLED495// @Group: SCR_496// @Path: ../libraries/AP_Scripting/AP_Scripting.cpp497GOBJECT(scripting, "SCR_", AP_Scripting),498#endif499500#if AP_STATS_ENABLED501// @Group: Node502// @Path: ../libraries/AP_Stats/AP_Stats.cpp503GOBJECT(node_stats, "STAT", AP_Stats),504#endif505506#if AP_PERIPH_EFI_ENABLED507// @Param: EFI_BAUDRATE508// @CopyFieldsFrom: RNGFND_BAUDRATE509// @DisplayName: EFI serial baudrate510// @Description: EFI serial baudrate.511GSCALAR(efi_baudrate, "EFI_BAUDRATE", HAL_PERIPH_EFI_BAUDRATE_DEFAULT),512513// @Param: EFI_PORT514// @DisplayName: EFI Serial Port515// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to EFI.516// @Range: 0 10517// @Increment: 1518// @User: Advanced519// @RebootRequired: True520GSCALAR(efi_port, "EFI_PORT", AP_PERIPH_EFI_PORT_DEFAULT),521522// EFI driver523// @Group: EFI524// @Path: ../libraries/AP_EFI/AP_EFI.cpp525GOBJECT(efi, "EFI", AP_EFI),526#endif527528#if AP_PERIPH_PROXIMITY_ENABLED529// @Param: PRX_BAUDRATE530// @CopyFieldsFrom: RNGFND_BAUDRATE531// @DisplayName: Proximity Sensor serial baudrate532// @Description: Proximity Sensor serial baudrate.533GSCALAR(proximity_baud, "PRX_BAUDRATE", HAL_PERIPH_RANGEFINDER_BAUDRATE_DEFAULT),534535// @Param: PRX_PORT536// @DisplayName: Proximity Sensor Serial Port537// @Description: This is the serial port number where SERIALx_PROTOCOL will be set to Proximity Sensor.538// @Range: 0 10539// @Increment: 1540// @User: Advanced541// @RebootRequired: True542GSCALAR(proximity_port, "PRX_PORT", AP_PERIPH_RANGEFINDER_PORT_DEFAULT),543544// @Param: PRX_MAX_RATE545// @DisplayName: Proximity Sensor max rate546// @Description: This is the maximum rate we send Proximity Sensor data in Hz. Zero means no limit547// @Units: Hz548// @Range: 0 200549// @Increment: 1550// @User: Advanced551GSCALAR(proximity_max_rate, "PRX_MAX_RATE", 50),552553// Proximity driver554// @Group: PRX555// @Path: ../libraries/AP_Proximity/AP_Proximity.cpp556GOBJECT(proximity, "PRX", AP_Proximity),557#endif // AP_PERIPH_PROXIMITY_ENABLED558559#if HAL_NMEA_OUTPUT_ENABLED560// @Group: NMEA_561// @Path: ../libraries/AP_NMEA_Output/AP_NMEA_Output.cpp562GOBJECT(nmea, "NMEA_", AP_NMEA_Output),563#endif564565#if AP_KDECAN_ENABLED566// @Group: KDE_567// @Path: ../libraries/AP_KDECAN/AP_KDECAN.cpp568GOBJECT(kdecan, "KDE_", AP_KDECAN),569#endif570571#if AP_PERIPH_ESC_APD_ENABLED572GARRAY(pole_count, 0, "ESC_NUM_POLES", 22),573#endif574575#if AP_PERIPH_ESC_APD_ENABLED576// @Param: ESC_APD_SERIAL_1577// @DisplayName: ESC APD Serial 1578// @Description: Which serial port to use for APD ESC data579// @Range: 0 6580// @Increment: 1581// @User: Advanced582// @RebootRequired: True583GARRAY(esc_serial_port, 0, "ESC_APD_SERIAL_1", APD_ESC_SERIAL_0),584585#if APD_ESC_INSTANCES > 1586GARRAY(esc_number, 1, "ESC_NUMBER2", 1),587588GARRAY(pole_count, 1, "ESC_NUM_POLES2", 22),589590// @Param: ESC_APD_SERIAL_2591// @DisplayName: ESC APD Serial 2592// @Description: Which serial port to use for APD ESC data593// @Range: 0 6594// @Increment: 1595// @User: Advanced596// @RebootRequired: True597GARRAY(esc_serial_port, 1, "ESC_APD_SERIAL_2", APD_ESC_SERIAL_1),598#endif599#endif600601#if AP_PERIPH_NETWORKING_ENABLED602// @Group: NET_603// @Path: networking.cpp604GOBJECT(networking_periph, "NET_", Networking_Periph),605#endif606607#if AP_PERIPH_RPM_ENABLED608// @Group: RPM609// @Path: ../libraries/AP_RPM/AP_RPM.cpp610GOBJECT(rpm_sensor, "RPM", AP_RPM),611#endif612613#if AP_PERIPH_RCIN_ENABLED614// @Group: RC615// @Path: rc_in.cpp616GOBJECT(g_rcin, "RC", Parameters_RCIN),617#endif618619#if AP_PERIPH_ACTUATOR_TELEM_ENABLED620// @Group: ACT621// @Path: actuator_telem.cpp622GOBJECT(actuator_telem, "ACT", ActuatorTelem),623#endif624625#if AP_PERIPH_BATTERY_BALANCE_ENABLED626// @Group: BAL627// @Path: batt_balance.cpp628GOBJECT(battery_balance, "BAL", BattBalance),629#endif630631#if AP_PERIPH_BATTERY_TAG_ENABLED632// @Group: BTAG633// @Path: battery_tag.cpp634GOBJECT(battery_tag, "BTAG", BatteryTag),635#endif636637#if AP_PERIPH_SERIAL_OPTIONS_ENABLED638// @Group: UART639// @Path: serial_options.cpp640GOBJECT(serial_options, "UART", SerialOptions),641#endif642643// NOTE: sim parameters should go last644#if AP_SIM_PARAM_ENABLED645// @Group: SIM_646// @Path: ../libraries/SITL/SITL.cpp647GOBJECT(sitl, "SIM_", SITL::SIM),648649#if AP_AHRS_ENABLED650// @Group: AHRS_651// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp652GOBJECT(ahrs, "AHRS_", AP_AHRS),653#endif654#endif // AP_SIM_ENABLED655656#if HAL_PERIPH_CAN_MIRROR657// @Param: CAN_MIRROR_PORTS658// @DisplayName: CAN ports to mirror traffic between659// @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.660// @Bitmask: 0:CAN1, 1:CAN2, 2:CAN3661// @User: Advanced662GSCALAR(can_mirror_ports, "CAN_MIRROR_PORTS", 0),663#endif // HAL_PERIPH_CAN_MIRROR664665#if AP_PERIPH_RTC_ENABLED666// @Group: RTC667// @Path: ../libraries/AP_RTC/AP_RTC.cpp668GOBJECT(rtc, "RTC", AP_RTC),669#endif670671#if AP_PERIPH_RELAY_ENABLED672// @Group: RELAY673// @Path: ../libraries/AP_Relay/AP_Relay.cpp674GOBJECT(relay, "RELAY", AP_Relay),675#endif676677#if AP_PERIPH_DEVICE_TEMPERATURE_ENABLED678// @Param: TEMP_MSG_RATE679// @DisplayName: Temperature sensor message rate680// @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.681// @Units: Hz682// @Range: 0 200683// @Increment: 1684// @User: Standard685GSCALAR(temperature_msg_rate, "TEMP_MSG_RATE", 0),686#endif687688// @Param: OPTIONS689// @DisplayName: AP Periph Options690// @Description: Bitmask of AP Periph Options691// @Bitmask: 0: Enable continuous sensor probe692// @User: Standard693GSCALAR(options, "OPTIONS", AP_PERIPH_PROBE_CONTINUOUS),694695#if AP_PERIPH_RPM_STREAM_ENABLED696// @Param: RPM_MSG_RATE697// @DisplayName: RPM sensor message rate698// @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.699// @Units: Hz700// @Range: 0 200701// @Increment: 1702// @User: Standard703GSCALAR(rpm_msg_rate, "RPM_MSG_RATE", 0),704#endif705706#if AP_EXTENDED_ESC_TELEM_ENABLED && HAL_WITH_ESC_TELEM707// @Param: ESC_EXT_TLM_RATE708// @DisplayName: ESC Extended telemetry message rate709// @Description: This is the rate at which extended ESC Telemetry will be sent across the CAN bus for each ESC710// @Units: Hz711// @Range: 0 50712// @Increment: 1713// @User: Advanced714GSCALAR(esc_extended_telem_rate, "ESC_EXT_TLM_RATE", AP_PERIPH_ESC_TELEM_RATE_DEFAULT / 10),715#endif716717718#if AP_PERIPH_IMU_ENABLED719// @Param: IMU_SAMPLE_RATE720// @DisplayName: IMU Sample Rate721// @Description: IMU Sample Rate722// @Range: 0 1000723// @User: Standard724GSCALAR(imu_sample_rate, "INS_SAMPLE_RATE", 0),725726// @Group: INS727// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp728GOBJECT(imu, "INS", AP_InertialSensor),729#endif730731#if AP_DAC_ENABLED732// @Group: DAC733// @Path: ../libraries/AP_DAC/AP_DAC.cpp734GOBJECT(dac, "DAC", AP_DAC),735#endif736737#if HAL_GCS_ENABLED738// @Group: MAV739// @Path: ../libraries/GCS_MAVLink/GCS.cpp740GOBJECT(_gcs, "MAV", GCS),741#endif742743#if AP_PERIPH_RC_OUT_ENABLED744// @Param: SRV_CMD_TIME_OUT745// @DisplayName: Servo Command Timeout746// @Description: This is the duration (ms) with which to hold the last driven servo command before timing out and zeroing the servo 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.747// @Range: 0 10000748// @Units: ms749// @User: Advanced750GSCALAR(servo_command_timeout_ms, "SRV_CMD_TIME_OUT", 200),751#endif752753AP_VAREND754};755756757void AP_Periph_FW::load_parameters(void)758{759AP_Param::setup_sketch_defaults();760761AP_Param::check_var_info();762763if (!g.format_version.load() ||764g.format_version != Parameters::k_format_version) {765// erase all parameters766StorageManager::erase();767AP_Param::erase_all();768769// save the current format version770g.format_version.set_and_save(Parameters::k_format_version);771}772g.format_version.set_default(Parameters::k_format_version);773774// Load all auto-loaded EEPROM variables775AP_Param::load_all();776}777778779