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/AntennaTracker/Parameters.cpp
Views: 1798
#include "Tracker.h"12/*3* AntennaTracker parameter definitions4*5*/67const AP_Param::Info Tracker::var_info[] = {8// @Param: FORMAT_VERSION9// @DisplayName: Eeprom format version number10// @Description: This value is incremented when changes are made to the eeprom format11// @User: Advanced12GSCALAR(format_version, "FORMAT_VERSION", 0),1314// @Param: SYSID_THISMAV15// @DisplayName: MAVLink system ID of this vehicle16// @Description: Allows setting an individual system id for this vehicle to distinguish it from others on the same network17// @Range: 1 25518// @User: Advanced19GSCALAR(sysid_this_mav, "SYSID_THISMAV", MAV_SYSTEM_ID),2021// @Param: SYSID_MYGCS22// @DisplayName: Ground station MAVLink system ID23// @Description: The identifier of the ground station in the MAVLink protocol. Don't change this unless you also modify the ground station to match.24// @Range: 1 25525// @Increment: 126// @User: Advanced27GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),2829// @Param: SYSID_TARGET30// @DisplayName: Target vehicle's MAVLink system ID31// @Description: The identifier of the vehicle being tracked. This should be zero (to auto detect) or be the same as the SYSID_THISMAV parameter of the vehicle being tracked.32// @Range: 1 25533// @User: Advanced34GSCALAR(sysid_target, "SYSID_TARGET", 0),3536// @Param: YAW_SLEW_TIME37// @DisplayName: Time for yaw to slew through its full range38// @Description: This controls how rapidly the tracker will change the servo output for yaw. It is set as the number of seconds to do a full rotation. You can use this parameter to slow the trackers movements, which may help with some types of trackers. A value of zero will allow for unlimited servo movement per update.39// @Units: s40// @Increment: 0.141// @Range: 0 2042// @User: Standard43GSCALAR(yaw_slew_time, "YAW_SLEW_TIME", 2),4445// @Param: PITCH_SLEW_TIME46// @DisplayName: Time for pitch to slew through its full range47// @Description: This controls how rapidly the tracker will change the servo output for pitch. It is set as the number of seconds to do a full range of pitch movement. You can use this parameter to slow the trackers movements, which may help with some types of trackers. A value of zero will allow for unlimited servo movement per update.48// @Units: s49// @Increment: 0.150// @Range: 0 2051// @User: Standard52GSCALAR(pitch_slew_time, "PITCH_SLEW_TIME", 2),5354// @Param: MIN_REVERSE_TIME55// @DisplayName: Minimum time to apply a yaw reversal56// @Description: When the tracker detects it has reached the limit of servo movement in yaw it will reverse and try moving to the other extreme of yaw. This parameter controls the minimum time it should reverse for. It is used to cope with trackers that have a significant lag in movement to ensure they do move all the way around.57// @Units: s58// @Increment: 159// @Range: 0 2060// @User: Standard61GSCALAR(min_reverse_time, "MIN_REVERSE_TIME", 1),6263// @Param: START_LATITUDE64// @DisplayName: Initial Latitude before GPS lock65// @Description: Combined with START_LONGITUDE this parameter allows for an initial position of the tracker to be set. This position will be used until the GPS gets lock. It can also be used to run a stationary tracker with no GPS attached.66// @Units: deg67// @Increment: 0.00000168// @Range: -90 9069// @User: Standard70GSCALAR(start_latitude, "START_LATITUDE", 0),7172// @Param: START_LONGITUDE73// @DisplayName: Initial Longitude before GPS lock74// @Description: Combined with START_LATITUDE this parameter allows for an initial position of the tracker to be set. This position will be used until the GPS gets lock. It can also be used to run a stationary tracker with no GPS attached.75// @Units: deg76// @Increment: 0.00000177// @Range: -180 18078// @User: Standard79GSCALAR(start_longitude, "START_LONGITUDE", 0),8081// @Param: STARTUP_DELAY82// @DisplayName: Delay before first servo movement from trim83// @Description: This parameter can be used to force the servos to their trim value for a time on startup. This can help with some servo types84// @Units: s85// @Increment: 0.186// @Range: 0 1087// @User: Standard88GSCALAR(startup_delay, "STARTUP_DELAY", 0),8990// @Param: SERVO_PITCH_TYPE91// @DisplayName: Type of servo system being used for pitch92// @Description: This allows selection of position servos or on/off servos for pitch93// @Values: 0:Position,1:OnOff,2:ContinuousRotation94// @User: Standard95GSCALAR(servo_pitch_type, "SERVO_PITCH_TYPE", SERVO_TYPE_POSITION),9697// @Param: SERVO_YAW_TYPE98// @DisplayName: Type of servo system being used for yaw99// @Description: This allows selection of position servos or on/off servos for yaw100// @Values: 0:Position,1:OnOff,2:ContinuousRotation101// @User: Standard102GSCALAR(servo_yaw_type, "SERVO_YAW_TYPE", SERVO_TYPE_POSITION),103104// @Param: ONOFF_YAW_RATE105// @DisplayName: Yaw rate for on/off servos106// @Description: Rate of change of yaw in degrees/second for on/off servos107// @Units: deg/s108// @Increment: 0.1109// @Range: 0 50110// @User: Standard111GSCALAR(onoff_yaw_rate, "ONOFF_YAW_RATE", 9.0f),112113// @Param: ONOFF_PITCH_RATE114// @DisplayName: Pitch rate for on/off servos115// @Description: Rate of change of pitch in degrees/second for on/off servos116// @Units: deg/s117// @Increment: 0.1118// @Range: 0 50119// @User: Standard120GSCALAR(onoff_pitch_rate, "ONOFF_PITCH_RATE", 1.0f),121122// @Param: ONOFF_YAW_MINT123// @DisplayName: Yaw minimum movement time124// @Description: Minimum amount of time in seconds to move in yaw125// @Units: s126// @Increment: 0.01127// @Range: 0 2128// @User: Standard129GSCALAR(onoff_yaw_mintime, "ONOFF_YAW_MINT", 0.1f),130131// @Param: ONOFF_PITCH_MINT132// @DisplayName: Pitch minimum movement time133// @Description: Minimum amount of time in seconds to move in pitch134// @Units: s135// @Increment: 0.01136// @Range: 0 2137// @User: Standard138GSCALAR(onoff_pitch_mintime, "ONOFF_PITCH_MINT", 0.1f),139140// @Param: YAW_TRIM141// @DisplayName: Yaw trim142// @Description: Amount of extra yaw to add when tracking. This allows for small adjustments for an out of trim compass.143// @Units: deg144// @Increment: 0.1145// @Range: -10 10146// @User: Standard147GSCALAR(yaw_trim, "YAW_TRIM", 0),148149// @Param: PITCH_TRIM150// @DisplayName: Pitch trim151// @Description: Amount of extra pitch to add when tracking. This allows for small adjustments for a badly calibrated barometer.152// @Units: deg153// @Increment: 0.1154// @Range: -10 10155// @User: Standard156GSCALAR(pitch_trim, "PITCH_TRIM", 0),157158// @Param: YAW_RANGE159// @DisplayName: Yaw Angle Range160// @Description: Yaw axis total range of motion in degrees161// @Units: deg162// @Increment: 0.1163// @Range: 0 360164// @User: Standard165GSCALAR(yaw_range, "YAW_RANGE", YAW_RANGE_DEFAULT),166167// @Param: DISTANCE_MIN168// @DisplayName: Distance minimum to target169// @Description: Tracker will track targets at least this distance away170// @Units: m171// @Increment: 1172// @Range: 0 100173// @User: Standard174GSCALAR(distance_min, "DISTANCE_MIN", DISTANCE_MIN_DEFAULT),175176// @Param: ALT_SOURCE177// @DisplayName: Altitude Source178// @Description: What provides altitude information for vehicle. Vehicle only assumes tracker has same altitude as vehicle's home179// @Values: 0:Barometer,1:GPS,2:GPS vehicle only180// @User: Standard181GSCALAR(alt_source, "ALT_SOURCE", 0),182183// @Param: MAV_UPDATE_RATE184// @DisplayName: Mavlink Update Rate185// @Description: The rate at which Mavlink updates position and baro data186// @Units: Hz187// @Increment: 1188// @Range: 1 10189// @User: Standard190GSCALAR(mavlink_update_rate, "MAV_UPDATE_RATE", 1),191192// @Param: PITCH_MIN193// @DisplayName: Minimum Pitch Angle194// @Description: The lowest angle the pitch can reach195// @Units: deg196// @Increment: 1197// @Range: -90 0198// @User: Standard199GSCALAR(pitch_min, "PITCH_MIN", PITCH_MIN_DEFAULT),200201// @Param: PITCH_MAX202// @DisplayName: Maximum Pitch Angle203// @Description: The highest angle the pitch can reach204// @Units: deg205// @Increment: 1206// @Range: 0 90207// @User: Standard208GSCALAR(pitch_max, "PITCH_MAX", PITCH_MAX_DEFAULT),209210// barometer library211// @Group: BARO212// @Path: ../libraries/AP_Baro/AP_Baro.cpp213GOBJECT(barometer, "BARO", AP_Baro),214215// @Group: COMPASS_216// @Path: ../libraries/AP_Compass/AP_Compass.cpp217GOBJECT(compass, "COMPASS_", Compass),218219// @Group: SCHED_220// @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp221GOBJECT(scheduler, "SCHED_", AP_Scheduler),222223// @Group: SR0_224// @Path: GCS_MAVLink_Tracker.cpp225GOBJECTN(_gcs.chan_parameters[0], gcs0, "SR0_", GCS_MAVLINK_Parameters),226227#if MAVLINK_COMM_NUM_BUFFERS >= 2228// @Group: SR1_229// @Path: GCS_MAVLink_Tracker.cpp230GOBJECTN(_gcs.chan_parameters[1], gcs1, "SR1_", GCS_MAVLINK_Parameters),231#endif232233#if MAVLINK_COMM_NUM_BUFFERS >= 3234// @Group: SR2_235// @Path: GCS_MAVLink_Tracker.cpp236GOBJECTN(_gcs.chan_parameters[2], gcs2, "SR2_", GCS_MAVLINK_Parameters),237#endif238239#if MAVLINK_COMM_NUM_BUFFERS >= 4240// @Group: SR3_241// @Path: GCS_MAVLink_Tracker.cpp242GOBJECTN(_gcs.chan_parameters[3], gcs3, "SR3_", GCS_MAVLINK_Parameters),243#endif244245#if MAVLINK_COMM_NUM_BUFFERS >= 5246// @Group: SR4_247// @Path: GCS_MAVLink_Tracker.cpp248GOBJECTN(_gcs.chan_parameters[4], gcs4, "SR4_", GCS_MAVLINK_Parameters),249#endif250251#if MAVLINK_COMM_NUM_BUFFERS >= 6252// @Group: SR5_253// @Path: GCS_MAVLink_Tracker.cpp254GOBJECTN(_gcs.chan_parameters[5], gcs5, "SR5_", GCS_MAVLINK_Parameters),255#endif256257#if MAVLINK_COMM_NUM_BUFFERS >= 7258// @Group: SR6_259// @Path: GCS_MAVLink_Tracker.cpp260GOBJECTN(_gcs.chan_parameters[6], gcs6, "SR6_", GCS_MAVLINK_Parameters),261#endif262263// @Param: LOG_BITMASK264// @DisplayName: Log bitmask265// @Description: 4 byte bitmap of log types to enable266// @Bitmask: 0:ATTITUDE,1:GPS,2:RCIN,3:IMU,4:RCOUT,5:COMPASS,6:Battery267// @User: Standard268GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),269270// @Group: INS271// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp272GOBJECT(ins, "INS", AP_InertialSensor),273274// @Group: AHRS_275// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp276GOBJECT(ahrs, "AHRS_", AP_AHRS),277278#if AP_SIM_ENABLED279// @Group: SIM_280// @Path: ../libraries/SITL/SITL.cpp281GOBJECT(sitl, "SIM_", SITL::SIM),282#endif283284// @Group: BRD_285// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp286GOBJECT(BoardConfig, "BRD_", AP_BoardConfig),287288#if HAL_MAX_CAN_PROTOCOL_DRIVERS289// @Group: CAN_290// @Path: ../libraries/AP_CANManager/AP_CANManager.cpp291GOBJECT(can_mgr, "CAN_", AP_CANManager),292#endif293294// GPS driver295// @Group: GPS296// @Path: ../libraries/AP_GPS/AP_GPS.cpp297GOBJECT(gps, "GPS", AP_GPS),298299// @Group: NTF_300// @Path: ../libraries/AP_Notify/AP_Notify.cpp301GOBJECT(notify, "NTF_", AP_Notify),302303// @Group: RC304// @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h305GOBJECT(rc_channels, "RC", RC_Channels_Tracker),306307// @Group: SERVO308// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp309GOBJECT(servo_channels, "SERVO", SRV_Channels),310311// AP_SerialManager was here312313// @Param: PITCH2SRV_P314// @DisplayName: Pitch axis controller P gain315// @Description: Pitch axis controller P gain. Converts the difference between desired pitch angle and actual pitch angle into a pitch servo pwm change316// @Range: 0.0 3.0317// @Increment: 0.01318// @User: Standard319320// @Param: PITCH2SRV_I321// @DisplayName: Pitch axis controller I gain322// @Description: Pitch axis controller I gain. Corrects long-term difference in desired pitch angle vs actual pitch angle323// @Range: 0.0 3.0324// @Increment: 0.01325// @User: Standard326327// @Param: PITCH2SRV_IMAX328// @DisplayName: Pitch axis controller I gain maximum329// @Description: Pitch axis controller I gain maximum. Constrains the maximum pwm change that the I gain will output330// @Range: 0 4000331// @Increment: 10332// @Units: d%333// @User: Standard334335// @Param: PITCH2SRV_D336// @DisplayName: Pitch axis controller D gain337// @Description: Pitch axis controller D gain. Compensates for short-term change in desired pitch angle vs actual pitch angle338// @Range: 0.001 0.1339// @Increment: 0.001340// @User: Standard341342// @Param: PITCH2SRV_FF343// @DisplayName: Pitch axis controller feed forward344// @Description: Pitch axis controller feed forward345// @Range: 0 0.5346// @Increment: 0.001347// @User: Standard348349// @Param: PITCH2SRV_FLTT350// @DisplayName: Pitch axis controller target frequency in Hz351// @Description: Pitch axis controller target frequency in Hz352// @Range: 1 50353// @Increment: 1354// @Units: Hz355// @User: Standard356357// @Param: PITCH2SRV_FLTE358// @DisplayName: Pitch axis controller error frequency in Hz359// @Description: Pitch axis controller error frequency in Hz360// @Range: 1 100361// @Increment: 1362// @Units: Hz363// @User: Standard364365// @Param: PITCH2SRV_FLTD366// @DisplayName: Pitch axis controller derivative frequency in Hz367// @Description: Pitch axis controller derivative frequency in Hz368// @Range: 1 100369// @Increment: 1370// @Units: Hz371// @User: Standard372373// @Param: PITCH2SRV_SMAX374// @DisplayName: Pitch slew rate limit375// @Description: Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.376// @Range: 0 200377// @Increment: 0.5378// @User: Advanced379380// @Param: PITCH2SRV_PDMX381// @DisplayName: Pitch axis controller PD sum maximum382// @Description: Pitch axis controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output383// @Range: 0 4000384// @Increment: 10385// @Units: d%386// @User: Advanced387388// @Param: PITCH2SRV_D_FF389// @DisplayName: Pitch Derivative FeedForward Gain390// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target391// @Range: 0 0.1392// @Increment: 0.001393// @User: Advanced394395// @Param: PITCH2SRV_NTF396// @DisplayName: Pitch Target notch filter index397// @Description: Pitch Target notch filter index398// @Range: 1 8399// @User: Advanced400401// @Param: PITCH2SRV_NEF402// @DisplayName: Pitch Error notch filter index403// @Description: Pitch Error notch filter index404// @Range: 1 8405// @User: Advanced406407GGROUP(pidPitch2Srv, "PITCH2SRV_", AC_PID),408409// @Param: YAW2SRV_P410// @DisplayName: Yaw axis controller P gain411// @Description: Yaw axis controller P gain. Converts the difference between desired yaw angle (heading) and actual yaw angle into a yaw servo pwm change412// @Range: 0.0 3.0413// @Increment: 0.01414// @User: Standard415416// @Param: YAW2SRV_I417// @DisplayName: Yaw axis controller I gain418// @Description: Yaw axis controller I gain. Corrects long-term difference in desired yaw angle (heading) vs actual yaw angle419// @Range: 0.0 3.0420// @Increment: 0.01421// @User: Standard422423// @Param: YAW2SRV_IMAX424// @DisplayName: Yaw axis controller I gain maximum425// @Description: Yaw axis controller I gain maximum. Constrains the maximum pwm change that the I gain will output426// @Range: 0 4000427// @Increment: 10428// @Units: d%429// @User: Standard430431// @Param: YAW2SRV_D432// @DisplayName: Yaw axis controller D gain433// @Description: Yaw axis controller D gain. Compensates for short-term change in desired yaw angle (heading) vs actual yaw angle434// @Range: 0.001 0.1435// @Increment: 0.001436// @User: Standard437438// @Param: YAW2SRV_FF439// @DisplayName: Yaw axis controller feed forward440// @Description: Yaw axis controller feed forward441// @Range: 0 0.5442// @Increment: 0.001443// @User: Standard444445// @Param: YAW2SRV_FLTT446// @DisplayName: Yaw axis controller target frequency in Hz447// @Description: Yaw axis controller target frequency in Hz448// @Range: 1 50449// @Increment: 1450// @Units: Hz451// @User: Standard452453// @Param: YAW2SRV_FLTE454// @DisplayName: Yaw axis controller error frequency in Hz455// @Description: Yaw axis controller error frequency in Hz456// @Range: 1 100457// @Increment: 1458// @Units: Hz459// @User: Standard460461// @Param: YAW2SRV_FLTD462// @DisplayName: Yaw axis controller derivative frequency in Hz463// @Description: Yaw axis controller derivative frequency in Hz464// @Range: 1 100465// @Increment: 1466// @Units: Hz467// @User: Standard468469// @Param: YAW2SRV_SMAX470// @DisplayName: Yaw slew rate limit471// @Description: Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.472// @Range: 0 200473// @Increment: 0.5474// @User: Advanced475476// @Param: YAW2SRV_PDMX477// @DisplayName: Yaw axis controller PD sum maximum478// @Description: Yaw axis controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output479// @Range: 0 4000480// @Increment: 10481// @Units: d%482// @User: Advanced483484// @Param: YAW2SRV_D_FF485// @DisplayName: Yaw Derivative FeedForward Gain486// @Description: FF D Gain which produces an output that is proportional to the rate of change of the target487// @Range: 0 0.1488// @Increment: 0.001489// @User: Advanced490491// @Param: YAW2SRV_NTF492// @DisplayName: Yaw Target notch filter index493// @Description: Yaw Target notch filter index494// @Range: 1 8495// @User: Advanced496497// @Param: YAW2SRV_NEF498// @DisplayName: Yaw Error notch filter index499// @Description: Yaw Error notch filter index500// @Range: 1 8501// @User: Advanced502503GGROUP(pidYaw2Srv, "YAW2SRV_", AC_PID),504505// @Param: CMD_TOTAL506// @DisplayName: Number of loaded mission items507// @Description: Set to 1 if HOME location has been loaded by the ground station. Do not change this manually.508// @Range: 1 255509// @User: Advanced510GSCALAR(command_total, "CMD_TOTAL", 0),511512// @Group: BATT513// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp514GOBJECT(battery, "BATT", AP_BattMonitor),515516// @Param: GCS_PID_MASK517// @DisplayName: GCS PID tuning mask518// @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for519// @User: Advanced520// @Bitmask: 0:Pitch,1:Yaw521GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0),522523// @Param: SCAN_SPEED_YAW524// @DisplayName: Speed at which to rotate the yaw axis in scan mode525// @Description: This controls how rapidly the tracker will move the servos in SCAN mode526// @Units: deg/s527// @Increment: 1528// @Range: 0 100529// @User: Standard530GSCALAR(scan_speed_yaw, "SCAN_SPEED_YAW", 2),531532// @Param: SCAN_SPEED_PIT533// @DisplayName: Speed at which to rotate pitch axis in scan mode534// @Description: This controls how rapidly the tracker will move the servos in SCAN mode535// @Units: deg/s536// @Increment: 1537// @Range: 0 100538// @User: Standard539GSCALAR(scan_speed_pitch, "SCAN_SPEED_PIT", 5),540541// @Param: INITIAL_MODE542// @DisplayName: Mode tracker will switch into after initialization543// @Description: 0:MANUAL, 1:STOP, 2:SCAN, 10:AUTO544// @User: Standard545GSCALAR(initial_mode, "INITIAL_MODE", 10),546547// @Param: SAFE_DISARM_PWM548// @DisplayName: PWM that will be output when disarmed or in stop mode549// @Description: 0:zero pwm, 1:trim pwm550// @User: Standard551GSCALAR(disarm_pwm, "SAFE_DISARM_PWM", 0),552553// @Param: AUTO_OPTIONS554// @DisplayName: Auto mode options555// @Description: 1: Scan for unknown target556// @User: Standard557// @Bitmask: 0:Scan for unknown target558GSCALAR(auto_opts, "AUTO_OPTIONS", 0),559560// @Group:561// @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp562PARAM_VEHICLE_INFO,563564#if HAL_NAVEKF2_AVAILABLE565// @Group: EK2_566// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp567GOBJECTN(ahrs.EKF2, NavEKF2, "EK2_", NavEKF2),568#endif569570#if HAL_NAVEKF3_AVAILABLE571// @Group: EK3_572// @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp573GOBJECTN(ahrs.EKF3, NavEKF3, "EK3_", NavEKF3),574#endif575576AP_VAREND577};578579580void Tracker::load_parameters(void)581{582AP_Vehicle::load_parameters(g.format_version, Parameters::k_format_version);583584#if AP_STATS_ENABLED585// PARAMETER_CONVERSION - Added: Jan-2024586AP_Param::convert_class(g.k_param_stats_old, &stats, stats.var_info, 0, true);587#endif588589#if AP_SCRIPTING_ENABLED590// PARAMETER_CONVERSION - Added: Jan-2024591AP_Param::convert_class(g.k_param_scripting_old, &scripting, scripting.var_info, 0, true);592#endif593594// PARAMETER_CONVERSION - Added: Feb-2024 for Tracker-4.6595#if HAL_LOGGING_ENABLED596AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, true);597#endif598599static const AP_Param::TopLevelObjectConversion toplevel_conversions[] {600#if AP_SERIALMANAGER_ENABLED601// PARAMETER_CONVERSION - Added: Feb-2024 for Tracker-4.6602{ &serial_manager, serial_manager.var_info, Parameters::k_param_serial_manager_old },603#endif604};605606AP_Param::convert_toplevel_objects(toplevel_conversions, ARRAY_SIZE(toplevel_conversions));607608#if HAL_HAVE_SAFETY_SWITCH609// configure safety switch to allow stopping the motors while armed610AP_Param::set_default_by_name("BRD_SAFETYOPTION", AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_OFF|611AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_ON|612AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_ARMED);613#endif614}615616617