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/Rover/Parameters.cpp
Views: 1798
#include "Rover.h"12#include <AP_Gripper/AP_Gripper.h>34/*5Rover parameter definitions6*/78const AP_Param::Info Rover::var_info[] = {9// @Param: FORMAT_VERSION10// @DisplayName: Eeprom format version number11// @Description: This value is incremented when changes are made to the eeprom format12// @User: Advanced13GSCALAR(format_version, "FORMAT_VERSION", 1),1415// @Param: LOG_BITMASK16// @DisplayName: Log bitmask17// @Description: Bitmap of what log types to enable in on-board logger. This value is made up of the sum of each of the log types you want to be saved. On boards supporting microSD cards or other large block-storage devices it is usually best just to enable all basic log types by setting this to 65535.18// @Bitmask: 0:Fast Attitude,1:Medium Attitude,2:GPS,3:System Performance,4:Throttle,5:Navigation Tuning,7:IMU,8:Mission Commands,9:Battery Monitor,10:Rangefinder,11:Compass,12:Camera,13:Steering,14:RC Input-Output,19:Raw IMU,20:Video Stabilization,21:Optical Flow19// @User: Advanced20GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),2122// @Param: RST_SWITCH_CH23// @DisplayName: Reset Switch Channel24// @Description: RC channel to use to reset to last flight mode after geofence takeover.25// @User: Advanced26GSCALAR(reset_switch_chan, "RST_SWITCH_CH", 0),2728// @Param: INITIAL_MODE29// @DisplayName: Initial driving mode30// @Description: This selects the mode to start in on boot. This is useful for when you want to start in AUTO mode on boot without a receiver. Usually used in combination with when AUTO_TRIGGER_PIN or AUTO_KICKSTART.31// @CopyValuesFrom: MODE132// @User: Advanced33GSCALAR(initial_mode, "INITIAL_MODE", (int8_t)Mode::Number::MANUAL),3435// @Param: SYSID_THISMAV36// @DisplayName: MAVLink system ID of this vehicle37// @Description: Allows setting an individual MAVLink system id for this vehicle to distinguish it from others on the same network38// @Range: 1 25539// @User: Advanced40GSCALAR(sysid_this_mav, "SYSID_THISMAV", MAV_SYSTEM_ID),4142// @Param: SYSID_MYGCS43// @DisplayName: MAVLink ground station ID44// @Description: The identifier of the ground station in the MAVLink protocol. Don't change this unless you also modify the ground station to match.45// @Range: 1 25546// @Increment: 147// @User: Advanced48GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),4950// @Param: TELEM_DELAY51// @DisplayName: Telemetry startup delay52// @Description: The amount of time (in seconds) to delay radio telemetry to prevent an Xbee bricking on power up53// @User: Standard54// @Units: s55// @Range: 0 3056// @Increment: 157GSCALAR(telem_delay, "TELEM_DELAY", 0),5859// @Param: GCS_PID_MASK60// @DisplayName: GCS PID tuning mask61// @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for62// @User: Advanced63// @Bitmask: 0:Steering,1:Throttle,2:Pitch,3:Left Wheel,4:Right Wheel,5:Sailboat Heel,6:Velocity North,7:Velocity East64GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0),6566// @Param: AUTO_TRIGGER_PIN67// @DisplayName: Auto mode trigger pin68// @Description: pin number to use to enable the throttle in auto mode. If set to -1 then don't use a trigger, otherwise this is a pin number which if held low in auto mode will enable the motor to run. If the switch is released while in AUTO then the motor will stop again. This can be used in combination with INITIAL_MODE to give a 'press button to start' rover with no receiver.69// @Values: -1:Disabled,0:APM TriggerPin0,1:APM TriggerPin1,2:APM TriggerPin2,3:APM TriggerPin3,4:APM TriggerPin4,5:APM TriggerPin5,6:APM TriggerPin6,7:APM TriggerPin7,8:APM TriggerPin8,50:AUX1,51:AUX2,52:AUX3,53:AUX4,54:AUX5,55:AUX670// @User: Standard71GSCALAR(auto_trigger_pin, "AUTO_TRIGGER_PIN", -1),7273// @Param: AUTO_KICKSTART74// @DisplayName: Auto mode trigger kickstart acceleration75// @Description: X acceleration in meters/second/second to use to trigger the motor start in auto mode. If set to zero then auto throttle starts immediately when the mode switch happens, otherwise the rover waits for the X acceleration to go above this value before it will start the motor76// @Units: m/s/s77// @Range: 0 2078// @Increment: 0.179// @User: Standard80GSCALAR(auto_kickstart, "AUTO_KICKSTART", 0.0f),8182// @Param: CRUISE_SPEED83// @DisplayName: Target cruise speed in auto modes84// @Description: The target speed in auto missions.85// @Units: m/s86// @Range: 0 10087// @Increment: 0.188// @User: Standard89GSCALAR(speed_cruise, "CRUISE_SPEED", CRUISE_SPEED),909192// @Param: CRUISE_THROTTLE93// @DisplayName: Base throttle percentage in auto94// @Description: The base throttle percentage to use in auto mode. The CRUISE_SPEED parameter controls the target speed, but the rover starts with the CRUISE_THROTTLE setting as the initial estimate for how much throttle is needed to achieve that speed. It then adjusts the throttle based on how fast the rover is actually going.95// @Units: %96// @Range: 0 10097// @Increment: 198// @User: Standard99GSCALAR(throttle_cruise, "CRUISE_THROTTLE", 50),100101// @Param: PILOT_STEER_TYPE102// @DisplayName: Pilot input steering type103// @Description: Pilot RC input interpretation104// @Values: 0:Default,1:Two Paddles Input,2:Direction reversed when backing up,3:Direction unchanged when backing up105// @User: Standard106GSCALAR(pilot_steer_type, "PILOT_STEER_TYPE", 0),107108// @Param: FS_ACTION109// @DisplayName: Failsafe Action110// @Description: What to do on a failsafe event111// @Values: 0:Nothing,1:RTL,2:Hold,3:SmartRTL or RTL,4:SmartRTL or Hold,5:Terminate112// @User: Standard113GSCALAR(fs_action, "FS_ACTION", (int8_t)FailsafeAction::Hold),114115// @Param: FS_TIMEOUT116// @DisplayName: Failsafe timeout117// @Description: The time in seconds that a failsafe condition must persist before the failsafe action is triggered118// @Units: s119// @Range: 1 100120// @Increment: 0.5121// @User: Standard122GSCALAR(fs_timeout, "FS_TIMEOUT", 1.5),123124// @Param: FS_THR_ENABLE125// @DisplayName: Throttle Failsafe Enable126// @Description: The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel to a low value. This can be used to detect the RC transmitter going out of range. Failsafe will be triggered when the throttle channel goes below the FS_THR_VALUE for FS_TIMEOUT seconds.127// @Values: 0:Disabled,1:Enabled,2:Enabled Continue with Mission in Auto128// @User: Standard129GSCALAR(fs_throttle_enabled, "FS_THR_ENABLE", FS_THR_ENABLED),130131// @Param: FS_THR_VALUE132// @DisplayName: Throttle Failsafe Value133// @Description: The PWM level on the throttle channel below which throttle failsafe triggers.134// @Range: 910 1100135// @Increment: 1136// @User: Standard137GSCALAR(fs_throttle_value, "FS_THR_VALUE", 910),138139// @Param: FS_GCS_ENABLE140// @DisplayName: GCS failsafe enable141// @Description: Enable ground control station telemetry failsafe. When enabled the Rover will execute the FS_ACTION when it fails to receive MAVLink heartbeat packets for FS_TIMEOUT seconds.142// @Values: 0:Disabled,1:Enabled,2:Enabled Continue with Mission in Auto143// @User: Standard144GSCALAR(fs_gcs_enabled, "FS_GCS_ENABLE", FS_GCS_DISABLED),145146// @Param: FS_CRASH_CHECK147// @DisplayName: Crash check action148// @Description: What to do on a crash event. When enabled the rover will go to hold if a crash is detected.149// @Values: 0:Disabled,1:Hold,2:HoldAndDisarm150// @User: Standard151GSCALAR(fs_crash_check, "FS_CRASH_CHECK", FS_CRASH_DISABLE),152153// @Param: FS_EKF_ACTION154// @DisplayName: EKF Failsafe Action155// @Description: Controls the action that will be taken when an EKF failsafe is invoked156// @Values: 0:Disabled,1:Hold,2:ReportOnly157// @User: Advanced158GSCALAR(fs_ekf_action, "FS_EKF_ACTION", FS_EKF_HOLD),159160// @Param: FS_EKF_THRESH161// @DisplayName: EKF failsafe variance threshold162// @Description: Allows setting the maximum acceptable compass and velocity variance163// @Values: 0.6:Strict, 0.8:Default, 1.0:Relaxed164// @User: Advanced165GSCALAR(fs_ekf_thresh, "FS_EKF_THRESH", 0.8f),166167// @Param: MODE_CH168// @DisplayName: Mode channel169// @Description: RC Channel to use for driving mode control170// @User: Advanced171GSCALAR(mode_channel, "MODE_CH", MODE_CHANNEL),172173// @Param: MODE1174// @DisplayName: Mode1175// @Values: 0:Manual,1:Acro,3:Steering,4:Hold,5:Loiter,6:Follow,7:Simple,8:Dock,9:Circle,10:Auto,11:RTL,12:SmartRTL,15:Guided176// @User: Standard177// @Description: Driving mode for switch position 1 (910 to 1230 and above 2049)178GSCALAR(mode1, "MODE1", (int8_t)Mode::Number::MANUAL),179180// @Param: MODE2181// @DisplayName: Mode2182// @Description: Driving mode for switch position 2 (1231 to 1360)183// @CopyValuesFrom: MODE1184// @User: Standard185GSCALAR(mode2, "MODE2", (int8_t)Mode::Number::MANUAL),186187// @Param: MODE3188// @CopyFieldsFrom: MODE1189// @DisplayName: Mode3190// @Description: Driving mode for switch position 3 (1361 to 1490)191GSCALAR(mode3, "MODE3", (int8_t)Mode::Number::MANUAL),192193// @Param: MODE4194// @CopyFieldsFrom: MODE1195// @DisplayName: Mode4196// @Description: Driving mode for switch position 4 (1491 to 1620)197GSCALAR(mode4, "MODE4", (int8_t)Mode::Number::MANUAL),198199// @Param: MODE5200// @CopyFieldsFrom: MODE1201// @DisplayName: Mode5202// @Description: Driving mode for switch position 5 (1621 to 1749)203GSCALAR(mode5, "MODE5", (int8_t)Mode::Number::MANUAL),204205// @Param: MODE6206// @CopyFieldsFrom: MODE1207// @DisplayName: Mode6208// @Description: Driving mode for switch position 6 (1750 to 2049)209GSCALAR(mode6, "MODE6", (int8_t)Mode::Number::MANUAL),210211// variables not in the g class which contain EEPROM saved variables212213// @Group: COMPASS_214// @Path: ../libraries/AP_Compass/AP_Compass.cpp215GOBJECT(compass, "COMPASS_", Compass),216217// @Group: SCHED_218// @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp219GOBJECT(scheduler, "SCHED_", AP_Scheduler),220221// @Group: BARO222// @Path: ../libraries/AP_Baro/AP_Baro.cpp223GOBJECT(barometer, "BARO", AP_Baro),224225#if AP_RELAY_ENABLED226// @Group: RELAY227// @Path: ../libraries/AP_Relay/AP_Relay.cpp228GOBJECT(relay, "RELAY", AP_Relay),229#endif230231// @Group: RCMAP_232// @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp233GOBJECT(rcmap, "RCMAP_", RCMapper),234235// @Group: SR0_236// @Path: GCS_MAVLink_Rover.cpp237GOBJECTN(_gcs.chan_parameters[0], gcs0, "SR0_", GCS_MAVLINK_Parameters),238239#if MAVLINK_COMM_NUM_BUFFERS >= 2240// @Group: SR1_241// @Path: GCS_MAVLink_Rover.cpp242GOBJECTN(_gcs.chan_parameters[1], gcs1, "SR1_", GCS_MAVLINK_Parameters),243#endif244245#if MAVLINK_COMM_NUM_BUFFERS >= 3246// @Group: SR2_247// @Path: GCS_MAVLink_Rover.cpp248GOBJECTN(_gcs.chan_parameters[2], gcs2, "SR2_", GCS_MAVLINK_Parameters),249#endif250251#if MAVLINK_COMM_NUM_BUFFERS >= 4252// @Group: SR3_253// @Path: GCS_MAVLink_Rover.cpp254GOBJECTN(_gcs.chan_parameters[3], gcs3, "SR3_", GCS_MAVLINK_Parameters),255#endif256257#if MAVLINK_COMM_NUM_BUFFERS >= 5258// @Group: SR4_259// @Path: GCS_MAVLink_Rover.cpp260GOBJECTN(_gcs.chan_parameters[4], gcs4, "SR4_", GCS_MAVLINK_Parameters),261#endif262263#if MAVLINK_COMM_NUM_BUFFERS >= 6264// @Group: SR5_265// @Path: GCS_MAVLink_Rover.cpp266GOBJECTN(_gcs.chan_parameters[5], gcs5, "SR5_", GCS_MAVLINK_Parameters),267#endif268269#if MAVLINK_COMM_NUM_BUFFERS >= 7270// @Group: SR6_271// @Path: GCS_MAVLink_Rover.cpp272GOBJECTN(_gcs.chan_parameters[6], gcs6, "SR6_", GCS_MAVLINK_Parameters),273#endif274275// AP_SerialManager was here276277#if AP_RANGEFINDER_ENABLED278// @Group: RNGFND279// @Path: ../libraries/AP_RangeFinder/AP_RangeFinder.cpp280GOBJECT(rangefinder, "RNGFND", RangeFinder),281#endif282283// @Group: INS284// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp285GOBJECT(ins, "INS", AP_InertialSensor),286287#if AP_SIM_ENABLED288// @Group: SIM_289// @Path: ../libraries/SITL/SITL.cpp290GOBJECT(sitl, "SIM_", SITL::SIM),291#endif292293// @Group: AHRS_294// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp295GOBJECT(ahrs, "AHRS_", AP_AHRS),296297#if AP_CAMERA_ENABLED298// @Group: CAM299// @Path: ../libraries/AP_Camera/AP_Camera.cpp300GOBJECT(camera, "CAM", AP_Camera),301#endif302303#if AC_PRECLAND_ENABLED304// @Group: PLND_305// @Path: ../libraries/AC_PrecLand/AC_PrecLand.cpp306GOBJECT(precland, "PLND_", AC_PrecLand),307#endif308309#if HAL_MOUNT_ENABLED310// @Group: MNT311// @Path: ../libraries/AP_Mount/AP_Mount.cpp312GOBJECT(camera_mount, "MNT", AP_Mount),313#endif314315// @Group: ARMING_316// @Path: ../libraries/AP_Arming/AP_Arming.cpp317GOBJECT(arming, "ARMING_", AP_Arming),318319// @Group: BATT320// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp321GOBJECT(battery, "BATT", AP_BattMonitor),322323// @Group: BRD_324// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp325GOBJECT(BoardConfig, "BRD_", AP_BoardConfig),326327#if HAL_MAX_CAN_PROTOCOL_DRIVERS328// @Group: CAN_329// @Path: ../libraries/AP_CANManager/AP_CANManager.cpp330GOBJECT(can_mgr, "CAN_", AP_CANManager),331#endif332333// GPS driver334// @Group: GPS335// @Path: ../libraries/AP_GPS/AP_GPS.cpp336GOBJECT(gps, "GPS", AP_GPS),337338#if HAL_NAVEKF2_AVAILABLE339// @Group: EK2_340// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp341GOBJECTN(ahrs.EKF2, NavEKF2, "EK2_", NavEKF2),342#endif343344#if HAL_NAVEKF3_AVAILABLE345// @Group: EK3_346// @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp347GOBJECTN(ahrs.EKF3, NavEKF3, "EK3_", NavEKF3),348#endif349350#if AP_RPM_ENABLED351// @Group: RPM352// @Path: ../libraries/AP_RPM/AP_RPM.cpp353GOBJECT(rpm_sensor, "RPM", AP_RPM),354#endif355356// @Group: MIS_357// @Path: ../libraries/AP_Mission/AP_Mission.cpp358GOBJECTN(mode_auto.mission, mission, "MIS_", AP_Mission),359360#if AP_RSSI_ENABLED361// @Group: RSSI_362// @Path: ../libraries/AP_RSSI/AP_RSSI.cpp363GOBJECT(rssi, "RSSI_", AP_RSSI),364#endif365366// @Group: NTF_367// @Path: ../libraries/AP_Notify/AP_Notify.cpp368GOBJECT(notify, "NTF_", AP_Notify),369370#if HAL_BUTTON_ENABLED371// @Group: BTN_372// @Path: ../libraries/AP_Button/AP_Button.cpp373GOBJECT(button, "BTN_", AP_Button),374#endif375376// @Group:377// @Path: Parameters.cpp378GOBJECT(g2, "", ParametersG2),379380#if OSD_ENABLED || OSD_PARAM_ENABLED381// @Group: OSD382// @Path: ../libraries/AP_OSD/AP_OSD.cpp383GOBJECT(osd, "OSD", AP_OSD),384#endif385386#if AP_OPTICALFLOW_ENABLED387// @Group: FLOW388// @Path: ../libraries/AP_OpticalFlow/AP_OpticalFlow.cpp389GOBJECT(optflow, "FLOW", AP_OpticalFlow),390#endif391392// @Group:393// @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp394PARAM_VEHICLE_INFO,395396AP_VAREND397};398399/*4002nd group of parameters401*/402const AP_Param::GroupInfo ParametersG2::var_info[] = {403// 1 was AP_Stats404405// @Param: SYSID_ENFORCE406// @DisplayName: GCS sysid enforcement407// @Description: This controls whether packets from other than the expected GCS system ID will be accepted408// @Values: 0:NotEnforced,1:Enforced409// @User: Advanced410AP_GROUPINFO("SYSID_ENFORCE", 2, ParametersG2, sysid_enforce, 0),411412// @Group: SERVO413// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp414AP_SUBGROUPINFO(servo_channels, "SERVO", 3, ParametersG2, SRV_Channels),415416// @Group: RC417// @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h418AP_SUBGROUPINFO(rc_channels, "RC", 4, ParametersG2, RC_Channels_Rover),419420#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED421// @Group: AFS_422// @Path: ../libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp423AP_SUBGROUPINFO(afs, "AFS_", 5, ParametersG2, AP_AdvancedFailsafe),424#endif425426#if AP_BEACON_ENABLED427// @Group: BCN428// @Path: ../libraries/AP_Beacon/AP_Beacon.cpp429AP_SUBGROUPINFO(beacon, "BCN", 6, ParametersG2, AP_Beacon),430#endif431432// 7 was used by AP_VisualOdometry433434// @Group: MOT_435// @Path: ../libraries/AR_Motors/AP_MotorsUGV.cpp436AP_SUBGROUPINFO(motors, "MOT_", 8, ParametersG2, AP_MotorsUGV),437438// @Group: WENC439// @Path: ../libraries/AP_WheelEncoder/AP_WheelEncoder.cpp440AP_SUBGROUPINFO(wheel_encoder, "WENC", 9, ParametersG2, AP_WheelEncoder),441442// @Group: ATC443// @Path: ../libraries/APM_Control/AR_AttitudeControl.cpp444AP_SUBGROUPINFO(attitude_control, "ATC", 10, ParametersG2, AR_AttitudeControl),445446// @Param: TURN_RADIUS447// @DisplayName: Turn radius of vehicle448// @Description: Turn radius of vehicle in meters while at low speeds. Lower values produce tighter turns in steering mode449// @Units: m450// @Range: 0 10451// @Increment: 0.1452// @User: Standard453AP_GROUPINFO("TURN_RADIUS", 11, ParametersG2, turn_radius, 0.9),454455// @Param: ACRO_TURN_RATE456// @DisplayName: Acro mode turn rate maximum457// @Description: Acro mode turn rate maximum458// @Units: deg/s459// @Range: 0 360460// @Increment: 1461// @User: Standard462AP_GROUPINFO("ACRO_TURN_RATE", 12, ParametersG2, acro_turn_rate, 180.0f),463464// @Group: SRTL_465// @Path: ../libraries/AP_SmartRTL/AP_SmartRTL.cpp466AP_SUBGROUPINFO(smart_rtl, "SRTL_", 13, ParametersG2, AP_SmartRTL),467468// 14 was WP_SPEED and should not be re-used469470// @Param: RTL_SPEED471// @DisplayName: Return-to-Launch speed default472// @Description: Return-to-Launch speed default. If zero use WP_SPEED or CRUISE_SPEED.473// @Units: m/s474// @Range: 0 100475// @Increment: 0.1476// @User: Standard477AP_GROUPINFO("RTL_SPEED", 15, ParametersG2, rtl_speed, 0.0f),478479// @Param: FRAME_CLASS480// @DisplayName: Frame Class481// @Description: Frame Class482// @Values: 0:Undefined,1:Rover,2:Boat,3:BalanceBot483// @User: Standard484AP_GROUPINFO("FRAME_CLASS", 16, ParametersG2, frame_class, 1),485486#if HAL_PROXIMITY_ENABLED487// @Group: PRX488// @Path: ../libraries/AP_Proximity/AP_Proximity.cpp489AP_SUBGROUPINFO(proximity, "PRX", 18, ParametersG2, AP_Proximity),490#endif491492#if AP_AVOIDANCE_ENABLED493// @Group: AVOID_494// @Path: ../libraries/AC_Avoidance/AC_Avoid.cpp495AP_SUBGROUPINFO(avoid, "AVOID_", 19, ParametersG2, AC_Avoid),496#endif497498// 20 was PIVOT_TURN_RATE and should not be re-used499500// @Param: BAL_PITCH_MAX501// @DisplayName: BalanceBot Maximum Pitch502// @Description: Pitch angle in degrees at 100% throttle503// @Units: deg504// @Range: 0 15505// @Increment: 0.1506// @User: Standard507AP_GROUPINFO("BAL_PITCH_MAX", 21, ParametersG2, bal_pitch_max, 10),508509// @Param: CRASH_ANGLE510// @DisplayName: Crash Angle511// @Description: Pitch/Roll angle limit in degrees for crash check. Zero disables check512// @Units: deg513// @Range: 0 60514// @Increment: 1515// @User: Standard516AP_GROUPINFO("CRASH_ANGLE", 22, ParametersG2, crash_angle, 0),517518#if AP_FOLLOW_ENABLED519// @Group: FOLL520// @Path: ../libraries/AP_Follow/AP_Follow.cpp521AP_SUBGROUPINFO(follow, "FOLL", 23, ParametersG2, AP_Follow),522#endif523524// @Param: FRAME_TYPE525// @DisplayName: Frame Type526// @Description: Frame Type527// @Values: 0:Undefined,1:Omni3,2:OmniX,3:OmniPlus,4:Omni3Mecanum528// @User: Standard529// @RebootRequired: True530AP_GROUPINFO("FRAME_TYPE", 24, ParametersG2, frame_type, 0),531532// @Param: LOIT_TYPE533// @DisplayName: Loiter type534// @Description: Loiter behaviour when moving to the target point535// @Values: 0:Forward or reverse to target point,1:Always face bow towards target point,2:Always face stern towards target point536// @User: Standard537AP_GROUPINFO("LOIT_TYPE", 25, ParametersG2, loit_type, 0),538539#if HAL_SPRAYER_ENABLED540// @Group: SPRAY_541// @Path: ../libraries/AC_Sprayer/AC_Sprayer.cpp542AP_SUBGROUPINFO(sprayer, "SPRAY_", 26, ParametersG2, AC_Sprayer),543#endif544545// @Group: WRC546// @Path: ../libraries/AP_WheelEncoder/AP_WheelRateControl.cpp547AP_SUBGROUPINFO(wheel_rate_control, "WRC", 27, ParametersG2, AP_WheelRateControl),548549#if HAL_RALLY_ENABLED550// @Group: RALLY_551// @Path: AP_Rally.cpp,../libraries/AP_Rally/AP_Rally.cpp552AP_SUBGROUPINFO(rally, "RALLY_", 28, ParametersG2, AP_Rally_Rover),553#endif554555// @Param: SIMPLE_TYPE556// @DisplayName: Simple_Type557// @Description: Simple mode types558// @Values: 0:InitialHeading,1:CardinalDirections559// @User: Standard560// @RebootRequired: True561AP_GROUPINFO("SIMPLE_TYPE", 29, ParametersG2, simple_type, 0),562563// @Param: LOIT_RADIUS564// @DisplayName: Loiter radius565// @Description: Vehicle will drift when within this distance of the target position566// @Units: m567// @Range: 0 20568// @Increment: 1569// @User: Standard570AP_GROUPINFO("LOIT_RADIUS", 30, ParametersG2, loit_radius, 2),571572// @Group: WNDVN_573// @Path: ../libraries/AP_WindVane/AP_WindVane.cpp574AP_SUBGROUPINFO(windvane, "WNDVN_", 31, ParametersG2, AP_WindVane),575576// 32 to 36 were old sailboat params577578// 37 was airspeed579580// @Param: MIS_DONE_BEHAVE581// @DisplayName: Mission done behave582// @Description: Behaviour after mission completes583// @Values: 0:Hold in Auto Mode,1:Loiter in Auto Mode,2:Acro Mode,3:Manual Mode584// @User: Standard585AP_GROUPINFO("MIS_DONE_BEHAVE", 38, ParametersG2, mis_done_behave, 0),586587// 39 was AP_Gripper588589// @Param: BAL_PITCH_TRIM590// @DisplayName: Balance Bot pitch trim angle591// @Description: Balance Bot pitch trim for balancing. This offsets the tilt of the center of mass.592// @Units: deg593// @Range: -2 2594// @Increment: 0.1595// @User: Standard596AP_GROUPINFO("BAL_PITCH_TRIM", 40, ParametersG2, bal_pitch_trim, 0),597598// 41 was Scripting599600// @Param: STICK_MIXING601// @DisplayName: Stick Mixing602// @Description: When enabled, this adds steering user stick input in auto modes, allowing the user to have some degree of control without changing modes.603// @Values: 0:Disabled,1:Enabled604// @User: Advanced605AP_GROUPINFO("STICK_MIXING", 42, ParametersG2, stick_mixing, 0),606607// @Group: WP_608// @Path: ../libraries/AR_WPNav/AR_WPNav.cpp609AP_SUBGROUPINFO(wp_nav, "WP_", 43, ParametersG2, AR_WPNav_OA),610611// @Group: SAIL_612// @Path: sailboat.cpp613AP_SUBGROUPINFO(sailboat, "SAIL_", 44, ParametersG2, Sailboat),614615#if AP_OAPATHPLANNER_ENABLED616// @Group: OA_617// @Path: ../libraries/AC_Avoidance/AP_OAPathPlanner.cpp618AP_SUBGROUPINFO(oa, "OA_", 45, ParametersG2, AP_OAPathPlanner),619#endif620621// @Param: SPEED_MAX622// @DisplayName: Speed maximum623// @Description: Maximum speed vehicle can obtain at full throttle. If 0, it will be estimated based on CRUISE_SPEED and CRUISE_THROTTLE.624// @Units: m/s625// @Range: 0 30626// @Increment: 0.1627// @User: Advanced628AP_GROUPINFO("SPEED_MAX", 46, ParametersG2, speed_max, 0.0f),629630// @Param: LOIT_SPEED_GAIN631// @DisplayName: Loiter speed gain632// @Description: Determines how agressively LOITER tries to correct for drift from loiter point. Higher is faster but default should be acceptable.633// @Range: 0 5634// @Increment: 0.01635// @User: Advanced636AP_GROUPINFO("LOIT_SPEED_GAIN", 47, ParametersG2, loiter_speed_gain, 0.5f),637638// @Param: FS_OPTIONS639// @DisplayName: Failsafe Options640// @Description: Bitmask to enable failsafe options641// @Bitmask: 0:Failsafe enabled in Hold mode642// @User: Advanced643AP_GROUPINFO("FS_OPTIONS", 48, ParametersG2, fs_options, 0),644645#if HAL_TORQEEDO_ENABLED646// @Group: TRQ647// @Path: ../libraries/AP_Torqeedo/AP_Torqeedo.cpp648AP_SUBGROUPINFO(torqeedo, "TRQ", 49, ParametersG2, AP_Torqeedo),649#endif650651// @Group: PSC652// @Path: ../libraries/APM_Control/AR_PosControl.cpp653AP_SUBGROUPINFO(pos_control, "PSC", 51, ParametersG2, AR_PosControl),654655// @Param: GUID_OPTIONS656// @DisplayName: Guided mode options657// @Description: Options that can be applied to change guided mode behaviour658// @Bitmask: 6:SCurves used for navigation659// @User: Advanced660AP_GROUPINFO("GUID_OPTIONS", 52, ParametersG2, guided_options, 0),661662// @Param: MANUAL_OPTIONS663// @DisplayName: Manual mode options664// @Description: Manual mode specific options665// @Bitmask: 0:Enable steering speed scaling666// @User: Advanced667AP_GROUPINFO("MANUAL_OPTIONS", 53, ParametersG2, manual_options, 0),668669#if MODE_DOCK_ENABLED670// @Group: DOCK671// @Path: mode_dock.cpp672AP_SUBGROUPPTR(mode_dock_ptr, "DOCK", 54, ParametersG2, ModeDock),673#endif674675// @Param: MANUAL_STR_EXPO676// @DisplayName: Manual Steering Expo677// @Description: Manual steering expo to allow faster steering when stick at edges678// @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High679// @Range: -0.5 0.95680// @User: Advanced681AP_GROUPINFO("MANUAL_STR_EXPO", 55, ParametersG2, manual_steering_expo, 0),682683// @Param: FS_GCS_TIMEOUT684// @DisplayName: GCS failsafe timeout685// @Description: Timeout before triggering the GCS failsafe686// @Units: s687// @Range: 2 120688// @Increment: 1689// @User: Standard690AP_GROUPINFO("FS_GCS_TIMEOUT", 56, ParametersG2, fs_gcs_timeout, 5),691692// @Group: CIRC693// @Path: mode_circle.cpp694AP_SUBGROUPINFO(mode_circle, "CIRC", 57, ParametersG2, ModeCircle),695696AP_GROUPEND697};698699// These auxiliary channel param descriptions are here so that users of beta Mission Planner (which uses the master branch as its source of descriptions)700// can get them. These lines can be removed once Rover-3.6-beta testing begins or we improve the source of descriptions for GCSs.701//702// @Param: CH7_OPTION703// @DisplayName: Channel 7 option704// @Description: What to do use channel 7 for705// @Values: 0:Nothing,1:SaveWaypoint,2:LearnCruiseSpeed,3:ArmDisarm,4:Manual,5:Acro,6:Steering,7:Hold,8:Auto,9:RTL,10:SmartRTL,11:Guided,12:Loiter706// @User: Standard707708// @Param: AUX_CH709// @DisplayName: Auxiliary switch channel710// @Description: RC Channel to use for auxiliary functions including saving waypoints711// @User: Advanced712713// @Param: PIVOT_TURN_ANGLE714// @DisplayName: Pivot turn angle715// @Description: Navigation angle threshold in degrees to switch to pivot steering. This allows you to setup a skid steering rover to turn on the spot in auto mode when the angle it needs to turn it greater than this angle. An angle of zero means to disable pivot turning. Note that you will probably also want to set a low value for WP_RADIUS to get neat turns.716// @Units: deg717// @Range: 0 360718// @Increment: 1719// @User: Standard720721// @Param: PIVOT_TURN_RATE722// @DisplayName: Pivot turn rate723// @Description: Desired pivot turn rate in deg/s.724// @Units: deg/s725// @Range: 0 360726// @Increment: 1727// @User: Standard728729ParametersG2::ParametersG2(void)730:731#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED732afs(),733#endif734#if AP_BEACON_ENABLED735beacon(),736#endif737wheel_rate_control(wheel_encoder),738motors(wheel_rate_control),739attitude_control(),740smart_rtl(),741#if HAL_PROXIMITY_ENABLED742proximity(),743#endif744#if MODE_DOCK_ENABLED745mode_dock_ptr(&rover.mode_dock),746#endif747#if AP_AVOIDANCE_ENABLED748avoid(),749#endif750#if AP_FOLLOW_ENABLED751follow(),752#endif753windvane(),754wp_nav(attitude_control, pos_control),755sailboat(),756pos_control(attitude_control)757{758AP_Param::setup_object_defaults(this, var_info);759}760761762/*763This is a conversion table from old parameter values to new764parameter names. The startup code looks for saved values of the old765parameters and will copy them across to the new parameters if the766new parameter does not yet have a saved value. It then saves the new767value.768769Note that this works even if the old parameter has been removed. It770relies on the old k_param index not being removed771772The second column below is the index in the var_info[] table for the773old object. This should be zero for top level parameters.774*/775const AP_Param::ConversionInfo conversion_table[] = {776{ Parameters::k_param_battery_monitoring, 0, AP_PARAM_INT8, "BATT_MONITOR" },777{ Parameters::k_param_battery_volt_pin, 0, AP_PARAM_INT8, "BATT_VOLT_PIN" },778{ Parameters::k_param_battery_curr_pin, 0, AP_PARAM_INT8, "BATT_CURR_PIN" },779{ Parameters::k_param_volt_div_ratio, 0, AP_PARAM_FLOAT, "BATT_VOLT_MULT" },780{ Parameters::k_param_curr_amp_per_volt, 0, AP_PARAM_FLOAT, "BATT_AMP_PERVOLT" },781{ Parameters::k_param_pack_capacity, 0, AP_PARAM_INT32, "BATT_CAPACITY" },782{ Parameters::k_param_serial0_baud, 0, AP_PARAM_INT16, "SERIAL0_BAUD" },783{ Parameters::k_param_serial1_baud, 0, AP_PARAM_INT16, "SERIAL1_BAUD" },784{ Parameters::k_param_serial2_baud, 0, AP_PARAM_INT16, "SERIAL2_BAUD" },785{ Parameters::k_param_throttle_min_old, 0, AP_PARAM_INT8, "MOT_THR_MIN" },786{ Parameters::k_param_throttle_max_old, 0, AP_PARAM_INT8, "MOT_THR_MAX" },787{ Parameters::k_param_compass_enabled_deprecated, 0, AP_PARAM_INT8, "COMPASS_ENABLE" },788{ Parameters::k_param_waypoint_radius_old, 0, AP_PARAM_FLOAT, "WP_RADIUS" },789{ Parameters::k_param_g2, 299, AP_PARAM_INT16, "WP_PIVOT_ANGLE" },790{ Parameters::k_param_g2, 363, AP_PARAM_INT16, "WP_PIVOT_RATE" },791{ Parameters::k_param_g2, 491, AP_PARAM_FLOAT, "WP_PIVOT_DELAY" },792{ Parameters::k_param_g2, 32, AP_PARAM_FLOAT, "SAIL_ANGLE_MIN" },793{ Parameters::k_param_g2, 33, AP_PARAM_FLOAT, "SAIL_ANGLE_MAX" },794{ Parameters::k_param_g2, 34, AP_PARAM_FLOAT, "SAIL_ANGLE_IDEAL" },795{ Parameters::k_param_g2, 35, AP_PARAM_FLOAT, "SAIL_HEEL_MAX" },796{ Parameters::k_param_g2, 36, AP_PARAM_FLOAT, "SAIL_NO_GO_ANGLE" },797{ Parameters::k_param_arming, 2, AP_PARAM_INT16, "ARMING_CHECK" },798{ Parameters::k_param_turn_max_g_old, 0, AP_PARAM_FLOAT, "ATC_TURN_MAX_G" },799{ Parameters::k_param_g2, 82, AP_PARAM_INT8 , "PRX1_TYPE" },800{ Parameters::k_param_g2, 146, AP_PARAM_INT8 , "PRX1_ORIENT" },801{ Parameters::k_param_g2, 210, AP_PARAM_INT16, "PRX1_YAW_CORR" },802{ Parameters::k_param_g2, 274, AP_PARAM_INT16, "PRX1_IGN_ANG1" },803{ Parameters::k_param_g2, 338, AP_PARAM_INT8, "PRX1_IGN_WID1" },804{ Parameters::k_param_g2, 402, AP_PARAM_INT16, "PRX1_IGN_ANG2" },805{ Parameters::k_param_g2, 466, AP_PARAM_INT8, "PRX1_IGN_WID2" },806{ Parameters::k_param_g2, 530, AP_PARAM_INT16, "PRX1_IGN_ANG3" },807{ Parameters::k_param_g2, 594, AP_PARAM_INT8, "PRX1_IGN_WID3" },808{ Parameters::k_param_g2, 658, AP_PARAM_INT16, "PRX1_IGN_ANG4" },809{ Parameters::k_param_g2, 722, AP_PARAM_INT8, "PRX1_IGN_WID4" },810{ Parameters::k_param_g2, 1234, AP_PARAM_FLOAT, "PRX1_MIN" },811{ Parameters::k_param_g2, 1298, AP_PARAM_FLOAT, "PRX1_MAX" },812{ Parameters::k_param_g2, 113, AP_PARAM_INT8, "TRQ1_TYPE" },813{ Parameters::k_param_g2, 177, AP_PARAM_INT8, "TRQ1_ONOFF_PIN" },814{ Parameters::k_param_g2, 241, AP_PARAM_INT8, "TRQ1_DE_PIN" },815{ Parameters::k_param_g2, 305, AP_PARAM_INT16, "TRQ1_OPTIONS" },816{ Parameters::k_param_g2, 369, AP_PARAM_INT8, "TRQ1_POWER" },817{ Parameters::k_param_g2, 433, AP_PARAM_FLOAT, "TRQ1_SLEW_TIME" },818{ Parameters::k_param_g2, 497, AP_PARAM_FLOAT, "TRQ1_DIR_DELAY" },819};820821822void Rover::load_parameters(void)823{824AP_Vehicle::load_parameters(g.format_version, Parameters::k_format_version);825826AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table));827828AP_Param::set_frame_type_flags(AP_PARAM_FRAME_ROVER);829830SRV_Channels::set_default_function(CH_1, SRV_Channel::k_steering);831SRV_Channels::set_default_function(CH_3, SRV_Channel::k_throttle);832833if (is_balancebot()) {834g2.crash_angle.set_default(30);835}836837SRV_Channels::upgrade_parameters();838839// convert CH7_OPTION to RC7_OPTION for Rover-3.4 to 3.5 upgrade840const AP_Param::ConversionInfo ch7_option_info = { Parameters::k_param_ch7_option, 0, AP_PARAM_INT8, "RC7_OPTION" };841AP_Int8 ch7_opt_old;842if (AP_Param::find_old_parameter(&ch7_option_info, &ch7_opt_old)) {843const uint8_t ch7_opt_map[] = {0,7,50,41,51,52,53,54,16,4,42,55,56};844const uint8_t ch7_opt_old_val = (uint8_t)ch7_opt_old.get();845if (ch7_opt_old_val < ARRAY_SIZE(ch7_opt_map)) {846AP_Param::set_default_by_name(ch7_option_info.new_name, ch7_opt_map[ch7_opt_old_val]);847}848}849850// set AR_WPNav's WP_SPEED to be old WP_SPEED (if set) or CRUISE_SPEED (if set)851const AP_Param::ConversionInfo wp_speed_old_info = { Parameters::k_param_g2, 14, AP_PARAM_FLOAT, "WP_SPEED" };852const AP_Param::ConversionInfo cruise_speed_info = { Parameters::k_param_speed_cruise, 0, AP_PARAM_FLOAT, "WP_SPEED" };853AP_Float wp_speed_old;854if (AP_Param::find_old_parameter(&wp_speed_old_info, &wp_speed_old)) {855// old WP_SPEED parameter value was set so copy to new WP_SPEED856AP_Param::convert_old_parameter(&wp_speed_old_info, 1.0f);857} else {858// copy CRUISE_SPEED to new WP_SPEED859AP_Param::convert_old_parameter(&cruise_speed_info, 1.0f);860}861862// attitude control FF and FILT parameter changes for Rover-3.6863const AP_Param::ConversionInfo ff_and_filt_conversion_info[] = {864{ Parameters::k_param_g2, 24650, AP_PARAM_FLOAT, "ATC_STR_RAT_FLTE" },865{ Parameters::k_param_g2, 28746, AP_PARAM_FLOAT, "ATC_STR_RAT_FF" },866{ Parameters::k_param_g2, 24714, AP_PARAM_FLOAT, "ATC_SPEED_FLTE" },867{ Parameters::k_param_g2, 28810, AP_PARAM_FLOAT, "ATC_SPEED_FF" },868{ Parameters::k_param_g2, 25226, AP_PARAM_FLOAT, "ATC_BAL_FLTE" },869{ Parameters::k_param_g2, 29322, AP_PARAM_FLOAT, "ATC_BAL_FF" },870{ Parameters::k_param_g2, 25354, AP_PARAM_FLOAT, "ATC_SAIL_FLTE" },871{ Parameters::k_param_g2, 29450, AP_PARAM_FLOAT, "ATC_SAIL_FF" },872};873AP_Param::convert_old_parameters(&ff_and_filt_conversion_info[0], ARRAY_SIZE(ff_and_filt_conversion_info));874875// configure safety switch to allow stopping the motors while armed876#if HAL_HAVE_SAFETY_SWITCH877AP_Param::set_default_by_name("BRD_SAFETYOPTION", AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_OFF|878AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_ON|879AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_ARMED);880#endif881882#if AP_AIRSPEED_ENABLED | AP_AIS_ENABLED | AP_FENCE_ENABLED883// Find G2's Top Level Key884AP_Param::ConversionInfo info;885if (!AP_Param::find_top_level_key_by_pointer(&g2, info.old_key)) {886return;887}888#endif889890static const AP_Param::G2ObjectConversion g2_conversions[] {891#if AP_AIRSPEED_ENABLED892// PARAMETER_CONVERSION - Added: JAN-2022893{ &airspeed, airspeed.var_info, 37 },894#endif895#if AP_AIS_ENABLED896// PARAMETER_CONVERSION - Added: MAR-2022897{ &ais, ais.var_info, 50 },898#endif899#if AP_FENCE_ENABLED900// PARAMETER_CONVERSION - Added: Mar-2022901{ &fence, fence.var_info, 17 },902#endif903#if AP_STATS_ENABLED904// PARAMETER_CONVERSION - Added: Jan-2024 for Rover-4.6905{ &stats, stats.var_info, 1 },906#endif907#if AP_SCRIPTING_ENABLED908// PARAMETER_CONVERSION - Added: Jan-2024 for Rover-4.6909{ &scripting, scripting.var_info, 41 },910#endif911#if AP_GRIPPER_ENABLED912// PARAMETER_CONVERSION - Added: Feb-2024 for Copter-4.6913{ &gripper, gripper.var_info, 39 },914#endif915};916917AP_Param::convert_g2_objects(&g2, g2_conversions, ARRAY_SIZE(g2_conversions));918919// PARAMETER_CONVERSION - Added: Feb-2024 for Rover-4.6920#if HAL_LOGGING_ENABLED921AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, true);922#endif923924static const AP_Param::TopLevelObjectConversion toplevel_conversions[] {925#if AP_SERIALMANAGER_ENABLED926// PARAMETER_CONVERSION - Added: Feb-2024 for Rover-4.6927{ &serial_manager, serial_manager.var_info, Parameters::k_param_serial_manager_old },928#endif929};930931AP_Param::convert_toplevel_objects(toplevel_conversions, ARRAY_SIZE(toplevel_conversions));932933}934935936