2015-05-13 00:16:45 -03:00
# include "Rover.h"
2012-04-30 04:17:14 -03:00
/*
2014-03-13 02:26:14 -03:00
APMRover2 parameter definitions
2012-04-30 04:17:14 -03:00
*/
2015-05-12 04:00:25 -03:00
# define GSCALAR(v, name, def) { rover.g.v.vtype, name, Parameters::k_param_ ## v, &rover.g.v, {def_value:def} }
# define GGROUP(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, &rover.g.v, {group_info:class::var_info} }
# define GOBJECT(v, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## v, &rover.v, {group_info:class::var_info} }
# define GOBJECTN(v, pname, name, class) { AP_PARAM_GROUP, name, Parameters::k_param_ ## pname, &rover.v, {group_info : class::var_info} }
2012-08-06 22:24:20 -03:00
2015-10-25 14:03:46 -03:00
const AP_Param : : Info Rover : : var_info [ ] = {
2016-04-17 01:11:01 -03:00
// @Param: FORMAT_VERSION
// @DisplayName: Eeprom format version number
// @Description: This value is incremented when changes are made to the eeprom format
// @User: Advanced
2016-12-20 09:30:04 -04:00
GSCALAR ( format_version , " FORMAT_VERSION " , 1 ) ,
2013-05-20 23:21:38 -03:00
// @Param: LOG_BITMASK
// @DisplayName: Log bitmask
2017-07-13 08:36:44 -03:00
// @Description: Bitmap of what log types to enable in dataflash. This values is made up of the sum of each of the log types you want to be saved on dataflash. On a PX4 or Pixhawk the large storage size of a microSD card means it is usually best just to enable all log types by setting this to 65535. On APM2 the smaller 4 MByte dataflash means you need to be more selective in your logging or you may run out of log space while flying (in which case it will wrap and overwrite the start of the log). The individual bits are ATTITUDE_FAST=1, ATTITUDE_MEDIUM=2, GPS=4, PerformanceMonitoring=8, ControlTuning=16, NavigationTuning=32, Mode=64, IMU=128, Commands=256, Battery=512, Compass=1024, TECS=2048, Camera=4096, RCandServo=8192, Rangefinder=16384, Arming=32768, FullLogs=65535
2016-04-17 01:11:01 -03:00
// @Values: 0:Disabled,5190:APM2-Default,65535:PX4/Pixhawk-Default
2017-12-07 08:42:06 -04:00
// @Bitmask: 0:ATTITUDE_FAST,1:ATTITUDE_MED,2:GPS,3:PM,4:THR,5:NTUN,7:IMU,8:CMD,9:CURRENT,10:RANGEFINDER,11:COMPASS,12:CAMERA,13:STEERING,14:RC,15:ARM/DISARM,19:IMU_RAW
2013-05-20 23:21:38 -03:00
// @User: Advanced
2016-12-20 09:30:04 -04:00
GSCALAR ( log_bitmask , " LOG_BITMASK " , DEFAULT_LOG_BITMASK ) ,
2016-04-17 01:11:01 -03:00
2013-06-03 04:55:22 -03:00
// @Param: RST_SWITCH_CH
// @DisplayName: Reset Switch Channel
2016-12-20 09:30:04 -04:00
// @Description: RC channel to use to reset to last flight mode after geofence takeover.
2013-06-03 04:55:22 -03:00
// @User: Advanced
2016-12-20 09:30:04 -04:00
GSCALAR ( reset_switch_chan , " RST_SWITCH_CH " , 0 ) ,
2013-02-08 06:17:54 -04:00
2013-05-02 18:59:15 -03:00
// @Param: INITIAL_MODE
// @DisplayName: Initial driving mode
2015-08-17 18:25:58 -03:00
// @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.
2018-07-02 04:21:37 -03:00
// @Values: 0:Manual,1:Acro,3:Steering,4:Hold,5:Loiter,6:Follow,7:Simple,10:Auto,11:RTL,12:SmartRTL,15:Guided
2013-05-02 18:59:15 -03:00
// @User: Advanced
2018-06-06 03:41:17 -03:00
GSCALAR ( initial_mode , " INITIAL_MODE " , Mode : : Number : : MANUAL ) ,
2013-05-02 18:59:15 -03:00
2013-02-08 06:17:54 -04:00
// @Param: SYSID_THIS_MAV
2015-05-10 21:21:28 -03:00
// @DisplayName: MAVLink system ID of this vehicle
// @Description: Allows setting an individual MAVLink system id for this vehicle to distinguish it from others on the same network
2014-01-13 21:10:47 -04:00
// @Range: 1 255
2013-02-08 06:17:54 -04:00
// @User: Advanced
2016-12-20 09:30:04 -04:00
GSCALAR ( sysid_this_mav , " SYSID_THISMAV " , MAV_SYSTEM_ID ) ,
2013-02-08 06:17:54 -04:00
// @Param: SYSID_MYGCS
// @DisplayName: MAVLink ground station ID
2016-04-17 01:11:01 -03:00
// @Description: The identifier of the ground station in the MAVLink protocol. Don't change this unless you also modify the ground station to match.
2014-01-13 21:10:47 -04:00
// @Range: 1 255
2013-02-08 06:17:54 -04:00
// @User: Advanced
2016-12-20 09:30:04 -04:00
GSCALAR ( sysid_my_gcs , " SYSID_MYGCS " , 255 ) ,
2012-11-27 20:42:51 -04:00
// @Param: TELEM_DELAY
2016-12-20 09:30:04 -04:00
// @DisplayName: Telemetry startup delay
2012-11-27 20:42:51 -04:00
// @Description: The amount of time (in seconds) to delay radio telemetry to prevent an Xbee bricking on power up
// @User: Standard
2017-05-02 10:34:42 -03:00
// @Units: s
2016-08-29 03:28:47 -03:00
// @Range: 0 30
2012-11-27 20:42:51 -04:00
// @Increment: 1
2012-08-29 20:36:18 -03:00
GSCALAR ( telem_delay , " TELEM_DELAY " , 0 ) ,
2012-11-27 20:42:51 -04:00
2015-06-18 04:37:59 -03:00
// @Param: GCS_PID_MASK
// @DisplayName: GCS PID tuning mask
// @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for
// @User: Advanced
2018-09-25 10:09:47 -03:00
// @Values: 0:None,1:Steering,2:Throttle,4:Pitch,8:Left Wheel,16:Right Wheel,32:Sailboat Heel
// @Bitmask: 0:Steering,1:Throttle,2:Pitch,3:Left Wheel,4:Right Wheel,5:Sailboat Heel
2015-06-18 04:37:59 -03:00
GSCALAR ( gcs_pid_mask , " GCS_PID_MASK " , 0 ) ,
2013-10-20 19:09:57 -03:00
2016-08-28 09:26:06 -03:00
// @Param: MAG_ENABLE
2016-04-17 01:11:01 -03:00
// @DisplayName: Enable Compass
// @Description: Setting this to Enabled(1) will enable the compass. Setting this to Disabled(0) will disable the compass. Note that this is separate from COMPASS_USE. This will enable the low level senor, and will enable logging of magnetometer data. To use the compass for navigation you must also set COMPASS_USE to 1.
2013-02-08 06:17:54 -04:00
// @User: Standard
2012-11-27 20:42:51 -04:00
// @Values: 0:Disabled,1:Enabled
2016-12-20 09:30:04 -04:00
GSCALAR ( compass_enabled , " MAG_ENABLE " , MAGNETOMETER ) ,
// @Param: AUTO_TRIGGER_PIN
// @DisplayName: Auto mode trigger pin
// @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.
2017-01-05 13:49:12 -04:00
// @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:Pixhawk TriggerPin50,51:Pixhawk TriggerPin51,52:Pixhawk TriggerPin52,53:Pixhawk TriggerPin53,54:Pixhawk TriggerPin54,55:Pixhawk TriggerPin55
2016-12-20 09:30:04 -04:00
// @User: standard
GSCALAR ( auto_trigger_pin , " AUTO_TRIGGER_PIN " , - 1 ) ,
// @Param: AUTO_KICKSTART
// @DisplayName: Auto mode trigger kickstart acceleration
// @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 motor
// @Units: m/s/s
// @Range: 0 20
// @Increment: 0.1
// @User: standard
GSCALAR ( auto_kickstart , " AUTO_KICKSTART " , 0.0f ) ,
2013-03-21 19:38:25 -03:00
2013-02-08 06:17:54 -04:00
// @Param: CRUISE_SPEED
2013-02-21 17:38:13 -04:00
// @DisplayName: Target cruise speed in auto modes
2013-02-08 06:17:54 -04:00
// @Description: The target speed in auto missions.
// @Units: m/s
// @Range: 0 100
2013-02-07 18:21:22 -04:00
// @Increment: 0.1
// @User: Standard
2018-03-09 00:19:21 -04:00
GSCALAR ( speed_cruise , " CRUISE_SPEED " , CRUISE_SPEED ) ,
2013-02-08 06:17:54 -04:00
2014-02-16 19:08:59 -04:00
// @Param: PIVOT_TURN_ANGLE
// @DisplayName: Pivot turn angle
// @Description: Navigation angle threshold in degrees to switch to pivot steering when SKID_STEER_OUT is 1. 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.
2017-05-02 10:34:42 -03:00
// @Units: deg
2014-02-16 19:08:59 -04:00
// @Range: 0 360
// @Increment: 1
// @User: Standard
2018-04-19 04:32:48 -03:00
GSCALAR ( pivot_turn_angle , " PIVOT_TURN_ANGLE " , 60 ) ,
2014-02-16 19:08:59 -04:00
2013-02-08 06:17:54 -04:00
// @Param: CRUISE_THROTTLE
// @DisplayName: Base throttle percentage in auto
2013-02-21 17:38:13 -04:00
// @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.
2017-05-02 10:34:42 -03:00
// @Units: %
2013-02-08 06:17:54 -04:00
// @Range: 0 100
// @Increment: 1
// @User: Standard
2016-12-20 09:30:04 -04:00
GSCALAR ( throttle_cruise , " CRUISE_THROTTLE " , 50 ) ,
2013-02-08 06:17:54 -04:00
2017-11-27 09:11:45 -04:00
// @Param: PILOT_STEER_TYPE
// @DisplayName: Pilot input steering type
2013-03-14 21:04:33 -03:00
// @Description: Set this to 1 for skid steering input rovers (tank track style in RC controller). When enabled, servo1 is used for the left track control, servo3 is used for right track control
2017-11-27 09:11:45 -04:00
// @Values: 0:Default,1:Two Paddles Input,2:Direction reversed when backing up,3:Direction unchanged when backing up
2013-03-14 21:04:33 -03:00
// @User: Standard
2017-11-27 09:11:45 -04:00
GSCALAR ( pilot_steer_type , " PILOT_STEER_TYPE " , 0 ) ,
2013-03-14 21:04:33 -03:00
2013-02-08 06:17:54 -04:00
// @Param: FS_ACTION
// @DisplayName: Failsafe Action
// @Description: What to do on a failsafe event
2018-01-18 14:19:50 -04:00
// @Values: 0:Nothing,1:RTL,2:Hold,3:SmartRTL or RTL,4:SmartRTL or Hold
2013-02-08 06:17:54 -04:00
// @User: Standard
2016-12-20 09:30:04 -04:00
GSCALAR ( fs_action , " FS_ACTION " , 2 ) ,
2013-02-08 06:17:54 -04:00
// @Param: FS_TIMEOUT
// @DisplayName: Failsafe timeout
2018-10-31 02:29:10 -03:00
// @Description: The time in seconds that a failsafe condition must persist before the failsafe action is triggered
2017-05-02 10:34:42 -03:00
// @Units: s
2018-10-31 02:29:10 -03:00
// @Range: 1 100
// @Increment: 0.5
2013-02-08 06:17:54 -04:00
// @User: Standard
2018-10-31 02:29:10 -03:00
GSCALAR ( fs_timeout , " FS_TIMEOUT " , 1.5 ) ,
2013-02-08 06:17:54 -04:00
// @Param: FS_THR_ENABLE
2012-11-27 20:42:51 -04:00
// @DisplayName: Throttle Failsafe Enable
2013-03-29 08:46:58 -03:00
// @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.
2012-11-27 20:42:51 -04:00
// @Values: 0:Disabled,1:Enabled
// @User: Standard
2016-12-20 09:30:04 -04:00
GSCALAR ( fs_throttle_enabled , " FS_THR_ENABLE " , 1 ) ,
2012-11-27 20:42:51 -04:00
2013-02-08 06:17:54 -04:00
// @Param: FS_THR_VALUE
2012-11-27 20:42:51 -04:00
// @DisplayName: Throttle Failsafe Value
2016-04-17 01:11:01 -03:00
// @Description: The PWM level on the throttle channel below which throttle failsafe triggers.
2017-05-24 09:28:52 -03:00
// @Range: 910 1100
2013-06-18 03:57:11 -03:00
// @Increment: 1
2012-11-27 20:42:51 -04:00
// @User: Standard
2016-12-20 09:30:04 -04:00
GSCALAR ( fs_throttle_value , " FS_THR_VALUE " , 910 ) ,
2012-11-27 20:42:51 -04:00
2013-02-07 18:21:22 -04:00
// @Param: FS_GCS_ENABLE
2012-11-27 20:42:51 -04:00
// @DisplayName: GCS failsafe enable
2013-03-29 08:46:58 -03:00
// @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.
2012-11-27 20:42:51 -04:00
// @Values: 0:Disabled,1:Enabled
// @User: Standard
2016-12-20 09:30:04 -04:00
GSCALAR ( fs_gcs_enabled , " FS_GCS_ENABLE " , 0 ) ,
2013-02-08 06:17:54 -04:00
2016-11-21 12:08:24 -04:00
// @Param: FS_CRASH_CHECK
// @DisplayName: Crash check action
// @Description: What to do on a crash event. When enabled the rover will go to hold if a crash is detected.
2017-12-23 00:52:21 -04:00
// @Values: 0:Disabled,1:Hold,2:HoldAndDisarm
2016-11-21 12:08:24 -04:00
// @User: Standard
2017-03-15 00:01:49 -03:00
GSCALAR ( fs_crash_check , " FS_CRASH_CHECK " , FS_CRASH_DISABLE ) ,
2016-11-21 12:08:24 -04:00
2016-12-20 09:30:04 -04:00
// @Param: RNGFND_TRIGGR_CM
2018-06-29 02:23:30 -03:00
// @DisplayName: Object avoidance trigger distance
2016-12-20 09:30:04 -04:00
// @Description: The distance from an obstacle in centimeters at which the rangefinder triggers a turn to avoid the obstacle
2017-05-02 10:34:42 -03:00
// @Units: cm
2013-02-28 16:15:09 -04:00
// @Range: 0 1000
// @Increment: 1
2016-12-20 09:30:04 -04:00
// @User: Standard
2017-07-13 08:36:44 -03:00
GSCALAR ( rangefinder_trigger_cm , " RNGFND_TRIGGR_CM " , 100 ) ,
2013-02-28 16:15:09 -04:00
2016-12-20 09:30:04 -04:00
// @Param: RNGFND_TURN_ANGL
2018-06-29 02:23:30 -03:00
// @DisplayName: Object avoidance turn aggressiveness and direction
// @Description: The aggressiveness and direction of turn to avoid an obstacle. Large positive or negative values (i.e. -450 or 450) cause turns up to the vehicle's maximum lateral acceleration (TURN_MAX_G) while values near zero cause gentle turns. Positive means to turn right, negative means turn left.
2017-05-29 22:19:51 -03:00
// @Units: deg
2018-06-18 04:09:35 -03:00
// @Range: -450 450
2013-02-28 16:15:09 -04:00
// @Increment: 1
2016-12-20 09:30:04 -04:00
// @User: Standard
2017-07-13 08:36:44 -03:00
GSCALAR ( rangefinder_turn_angle , " RNGFND_TURN_ANGL " , 45 ) ,
2013-02-28 16:15:09 -04:00
2016-12-20 09:30:04 -04:00
// @Param: RNGFND_TURN_TIME
2018-06-29 02:23:30 -03:00
// @DisplayName: Object avoidance turn time
2016-12-20 09:30:04 -04:00
// @Description: The amount of time in seconds to apply the RNGFND_TURN_ANGL after detecting an obstacle.
2017-05-02 10:34:42 -03:00
// @Units: s
2013-02-28 16:15:09 -04:00
// @Range: 0 100
// @Increment: 0.1
2016-12-20 09:30:04 -04:00
// @User: Standard
2017-07-13 08:36:44 -03:00
GSCALAR ( rangefinder_turn_time , " RNGFND_TURN_TIME " , 1.0f ) ,
2013-02-28 16:15:09 -04:00
2016-12-20 09:30:04 -04:00
// @Param: RNGFND_DEBOUNCE
2018-06-29 02:23:30 -03:00
// @DisplayName: Object avoidance rangefinder debounce count
2017-07-13 08:36:44 -03:00
// @Description: The number of 50Hz rangefinder hits needed to trigger an obstacle avoidance event. If you get a lot of false rangefinder events then raise this number, but if you make it too large then it will cause lag in detecting obstacles, which could cause you go hit the obstacle.
2013-03-28 20:49:08 -03:00
// @Range: 1 100
// @Increment: 1
2016-12-20 09:30:04 -04:00
// @User: Standard
2017-07-13 08:36:44 -03:00
GSCALAR ( rangefinder_debounce , " RNGFND_DEBOUNCE " , 2 ) ,
2013-03-28 20:49:08 -03:00
2013-02-07 18:21:22 -04:00
// @Param: MODE_CH
// @DisplayName: Mode channel
2013-02-08 06:17:54 -04:00
// @Description: RC Channel to use for driving mode control
2012-11-27 20:42:51 -04:00
// @User: Advanced
2016-12-20 09:30:04 -04:00
GSCALAR ( mode_channel , " MODE_CH " , MODE_CHANNEL ) ,
2012-11-27 20:42:51 -04:00
2013-02-07 18:21:22 -04:00
// @Param: MODE1
// @DisplayName: Mode1
2018-07-02 04:21:37 -03:00
// @Values: 0:Manual,1:Acro,3:Steering,4:Hold,5:Loiter,6:Follow,7:Simple,10:Auto,11:RTL,12:SmartRTL,15:Guided
2012-11-27 20:42:51 -04:00
// @User: Standard
2013-02-08 06:17:54 -04:00
// @Description: Driving mode for switch position 1 (910 to 1230 and above 2049)
2018-06-06 03:41:17 -03:00
GSCALAR ( mode1 , " MODE1 " , Mode : : Number : : MANUAL ) ,
2012-11-27 20:42:51 -04:00
2013-02-07 18:21:22 -04:00
// @Param: MODE2
// @DisplayName: Mode2
2013-02-08 06:17:54 -04:00
// @Description: Driving mode for switch position 2 (1231 to 1360)
2018-07-02 04:21:37 -03:00
// @Values: 0:Manual,1:Acro,3:Steering,4:Hold,5:Loiter,6:Follow,7:Simple,10:Auto,11:RTL,12:SmartRTL,15:Guided
2012-11-27 20:42:51 -04:00
// @User: Standard
2018-06-06 03:41:17 -03:00
GSCALAR ( mode2 , " MODE2 " , Mode : : Number : : MANUAL ) ,
2012-11-27 20:42:51 -04:00
2013-02-07 18:21:22 -04:00
// @Param: MODE3
// @DisplayName: Mode3
2013-02-08 06:17:54 -04:00
// @Description: Driving mode for switch position 3 (1361 to 1490)
2018-07-02 04:21:37 -03:00
// @Values: 0:Manual,1:Acro,3:Steering,4:Hold,5:Loiter,6:Follow,7:Simple,10:Auto,11:RTL,12:SmartRTL,15:Guided
2012-11-27 20:42:51 -04:00
// @User: Standard
2018-06-06 03:41:17 -03:00
GSCALAR ( mode3 , " MODE3 " , Mode : : Number : : MANUAL ) ,
2012-11-27 20:42:51 -04:00
2013-02-07 18:21:22 -04:00
// @Param: MODE4
// @DisplayName: Mode4
2013-02-08 06:17:54 -04:00
// @Description: Driving mode for switch position 4 (1491 to 1620)
2018-07-02 04:21:37 -03:00
// @Values: 0:Manual,1:Acro,3:Steering,4:Hold,5:Loiter,6:Follow,7:Simple,10:Auto,11:RTL,12:SmartRTL,15:Guided
2012-11-27 20:42:51 -04:00
// @User: Standard
2018-06-06 03:41:17 -03:00
GSCALAR ( mode4 , " MODE4 " , Mode : : Number : : MANUAL ) ,
2012-11-27 20:42:51 -04:00
2013-02-07 18:21:22 -04:00
// @Param: MODE5
// @DisplayName: Mode5
2013-02-08 06:17:54 -04:00
// @Description: Driving mode for switch position 5 (1621 to 1749)
2018-07-02 04:21:37 -03:00
// @Values: 0:Manual,1:Acro,3:Steering,4:Hold,5:Loiter,6:Follow,7:Simple,10:Auto,11:RTL,12:SmartRTL,15:Guided
2012-11-27 20:42:51 -04:00
// @User: Standard
2018-06-06 03:41:17 -03:00
GSCALAR ( mode5 , " MODE5 " , Mode : : Number : : MANUAL ) ,
2012-11-27 20:42:51 -04:00
2013-02-07 18:21:22 -04:00
// @Param: MODE6
// @DisplayName: Mode6
2013-02-08 06:17:54 -04:00
// @Description: Driving mode for switch position 6 (1750 to 2049)
2018-07-02 04:21:37 -03:00
// @Values: 0:Manual,1:Acro,3:Steering,4:Hold,5:Loiter,6:Follow,7:Simple,10:Auto,11:RTL,12:SmartRTL,15:Guided
2012-11-27 20:42:51 -04:00
// @User: Standard
2018-06-06 03:41:17 -03:00
GSCALAR ( mode6 , " MODE6 " , Mode : : Number : : MANUAL ) ,
2012-08-06 22:24:20 -03:00
2013-02-08 06:17:54 -04:00
// @Param: WP_RADIUS
// @DisplayName: Waypoint radius
// @Description: The distance in meters from a waypoint when we consider the waypoint has been reached. This determines when the rover will turn along the next waypoint path.
2017-05-02 10:34:42 -03:00
// @Units: m
2013-02-08 06:17:54 -04:00
// @Range: 0 1000
// @Increment: 0.1
2012-12-18 07:44:12 -04:00
// @User: Standard
2016-12-20 09:30:04 -04:00
GSCALAR ( waypoint_radius , " WP_RADIUS " , 2.0f ) ,
2012-04-30 04:17:14 -03:00
2017-08-09 22:30:35 -03:00
// @Param: WP_OVERSHOOT
// @DisplayName: Waypoint overshoot maximum
// @Description: Waypoint overshoot maximum in meters. The vehicle will attempt to stay within this many meters of the track as it completes one waypoint and moves to the next.
// @Units: m
// @Range: 0 10
// @Increment: 0.1
// @User: Standard
GSCALAR ( waypoint_overshoot , " WP_OVERSHOOT " , 2.0f ) ,
2013-06-16 20:50:53 -03:00
// @Param: TURN_MAX_G
// @DisplayName: Turning maximum G force
// @Description: The maximum turning acceleration (in units of gravities) that the rover can handle while remaining stable. The navigation code will keep the lateral acceleration below this level to avoid rolling over or slipping the wheels in turns
// @Units: gravities
2018-04-01 14:02:39 -03:00
// @Range: 0.1 10
// @Increment: 0.01
2013-06-16 20:50:53 -03:00
// @User: Standard
2018-04-26 02:17:04 -03:00
GSCALAR ( turn_max_g , " TURN_MAX_G " , 0.6f ) ,
2013-06-16 20:50:53 -03:00
2016-12-20 09:30:04 -04:00
// variables not in the g class which contain EEPROM saved variables
2013-06-03 04:55:22 -03:00
// @Group: COMPASS_
2016-03-15 11:16:23 -03:00
// @Path: ../libraries/AP_Compass/AP_Compass.cpp
2016-12-20 09:30:04 -04:00
GOBJECT ( compass , " COMPASS_ " , Compass ) ,
2013-06-03 04:55:22 -03:00
2013-06-03 21:37:05 -03:00
// @Group: SCHED_
// @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp
GOBJECT ( scheduler , " SCHED_ " , AP_Scheduler ) ,
2014-02-23 18:25:50 -04:00
// barometer ground calibration. The GND_ prefix is chosen for
// compatibility with previous releases of ArduPlane
// @Group: GND_
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
GOBJECT ( barometer , " GND_ " , AP_Baro ) ,
2013-06-24 23:48:58 -03:00
// @Group: RELAY_
// @Path: ../libraries/AP_Relay/AP_Relay.cpp
GOBJECT ( relay , " RELAY_ " , AP_Relay ) ,
2013-06-03 06:33:59 -03:00
// @Group: RCMAP_
// @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp
GOBJECT ( rcmap , " RCMAP_ " , RCMapper ) ,
2013-09-11 20:51:36 -03:00
// @Group: SR0_
2015-05-20 22:42:59 -03:00
// @Path: GCS_Mavlink.cpp
2017-02-13 07:00:19 -04:00
GOBJECTN ( _gcs . _chan [ 0 ] , gcs0 , " SR0_ " , GCS_MAVLINK ) ,
2013-09-11 20:51:36 -03:00
2013-11-23 06:57:26 -04:00
// @Group: SR1_
2015-05-20 22:42:59 -03:00
// @Path: GCS_Mavlink.cpp
2017-02-13 07:00:19 -04:00
GOBJECTN ( _gcs . _chan [ 1 ] , gcs1 , " SR1_ " , GCS_MAVLINK ) ,
2013-11-23 06:57:26 -04:00
// @Group: SR2_
2015-05-20 22:42:59 -03:00
// @Path: GCS_Mavlink.cpp
2017-02-13 07:00:19 -04:00
GOBJECTN ( _gcs . _chan [ 2 ] , gcs2 , " SR2_ " , GCS_MAVLINK ) ,
2012-11-07 03:28:20 -04:00
2015-05-15 01:24:59 -03:00
// @Group: SR3_
2015-05-20 22:42:59 -03:00
// @Path: GCS_Mavlink.cpp
2017-02-13 07:00:19 -04:00
GOBJECTN ( _gcs . _chan [ 3 ] , gcs3 , " SR3_ " , GCS_MAVLINK ) ,
2015-05-15 01:24:59 -03:00
2015-01-28 00:56:36 -04:00
// @Group: SERIAL
// @Path: ../libraries/AP_SerialManager/AP_SerialManager.cpp
GOBJECT ( serial_manager , " SERIAL " , AP_SerialManager ) ,
2013-06-16 20:50:53 -03:00
// @Group: NAVL1_
// @Path: ../libraries/AP_L1_Control/AP_L1_Control.cpp
GOBJECT ( L1_controller , " NAVL1_ " , AP_L1_Control ) ,
2014-07-16 16:18:10 -03:00
// @Group: RNGFND
2014-06-27 00:18:20 -03:00
// @Path: ../libraries/AP_RangeFinder/RangeFinder.cpp
2017-07-13 08:36:44 -03:00
GOBJECT ( rangefinder , " RNGFND " , RangeFinder ) ,
2013-02-28 21:00:48 -04:00
2012-11-07 03:28:20 -04:00
// @Group: INS_
// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp
GOBJECT ( ins , " INS_ " , AP_InertialSensor ) ,
2012-08-06 22:24:20 -03:00
2015-05-04 03:18:29 -03:00
# if CONFIG_HAL_BOARD == HAL_BOARD_SITL
2012-11-27 08:20:25 -04:00
// @Group: SIM_
// @Path: ../libraries/SITL/SITL.cpp
2015-10-22 10:04:42 -03:00
GOBJECT ( sitl , " SIM_ " , SITL : : SITL ) ,
2012-11-27 08:20:25 -04:00
# endif
2012-11-17 02:45:20 -04:00
// @Group: AHRS_
// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
GOBJECT ( ahrs , " AHRS_ " , AP_AHRS ) ,
2013-07-14 20:57:00 -03:00
# if CAMERA == ENABLED
// @Group: CAM_
// @Path: ../libraries/AP_Camera/AP_Camera.cpp
GOBJECT ( camera , " CAM_ " , AP_Camera ) ,
# endif
# if MOUNT == ENABLED
2015-04-28 21:08:06 -03:00
// @Group: MNT
2013-07-14 20:57:00 -03:00
// @Path: ../libraries/AP_Mount/AP_Mount.cpp
2015-01-12 08:12:31 -04:00
GOBJECT ( camera_mount , " MNT " , AP_Mount ) ,
2013-07-14 20:57:00 -03:00
# endif
2015-10-30 02:56:41 -03:00
// @Group: ARMING_
// @Path: ../libraries/AP_Arming/AP_Arming.cpp
GOBJECT ( arming , " ARMING_ " , AP_Arming ) ,
2015-11-09 18:40:10 -04:00
// @Group: LOG
// @Path: ../libraries/DataFlash/DataFlash.cpp
GOBJECT ( DataFlash , " LOG " , DataFlash_Class ) ,
2015-08-25 23:15:16 -03:00
// @Group: BATT
2013-10-02 03:07:28 -03:00
// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp
2014-12-09 09:14:22 -04:00
GOBJECT ( battery , " BATT " , AP_BattMonitor ) ,
2013-10-02 03:07:28 -03:00
2014-01-19 21:57:59 -04:00
// @Group: BRD_
// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp
GOBJECT ( BoardConfig , " BRD_ " , AP_BoardConfig ) ,
2017-05-06 06:11:40 -03:00
# if HAL_WITH_UAVCAN
// @Group: CAN_
// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig_CAN.cpp
GOBJECT ( BoardConfig_CAN , " CAN_ " , AP_BoardConfig_CAN ) ,
# endif
2014-03-31 16:18:27 -03:00
// GPS driver
// @Group: GPS_
// @Path: ../libraries/AP_GPS/AP_GPS.cpp
GOBJECT ( gps , " GPS_ " , AP_GPS ) ,
2017-08-10 01:14:33 -03:00
# if AP_AHRS_NAVEKF_AVAILABLE
// @Group: EK2_
// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp
GOBJECTN ( EKF2 , NavEKF2 , " EK2_ " , NavEKF2 ) ,
// @Group: EK3_
// @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp
GOBJECTN ( EKF3 , NavEKF3 , " EK3_ " , NavEKF3 ) ,
# endif
2014-02-21 00:51:34 -04:00
2014-03-10 05:42:44 -03:00
// @Group: MIS_
// @Path: ../libraries/AP_Mission/AP_Mission.cpp
GOBJECT ( mission , " MIS_ " , AP_Mission ) ,
2016-12-20 09:30:04 -04:00
2015-08-28 03:00:12 -03:00
// @Group: RSSI_
// @Path: ../libraries/AP_RSSI/AP_RSSI.cpp
2016-12-20 09:30:04 -04:00
GOBJECT ( rssi , " RSSI_ " , AP_RSSI ) ,
2014-03-10 05:42:44 -03:00
2015-12-03 16:48:16 -04:00
// @Group: NTF_
// @Path: ../libraries/AP_Notify/AP_Notify.cpp
GOBJECT ( notify , " NTF_ " , AP_Notify ) ,
2016-07-21 22:24:35 -03:00
// @Group: BTN_
// @Path: ../libraries/AP_Button/AP_Button.cpp
GOBJECT ( button , " BTN_ " , AP_Button ) ,
2016-10-25 22:37:08 -03:00
// @Group:
// @Path: Parameters.cpp
GOBJECT ( g2 , " " , ParametersG2 ) ,
2018-08-27 16:55:29 -03:00
# if OSD_ENABLED == ENABLED
// @Group: OSD
// @Path: ../libraries/AP_OSD/AP_OSD.cpp
GOBJECT ( osd , " OSD " , AP_OSD ) ,
# endif
2016-12-20 09:30:04 -04:00
AP_VAREND
2012-04-30 04:17:14 -03:00
} ;
2016-10-25 22:37:08 -03:00
/*
2 nd group of parameters
*/
const AP_Param : : GroupInfo ParametersG2 : : var_info [ ] = {
2018-02-28 08:23:09 -04:00
# if STATS_ENABLED == ENABLED
2016-10-25 23:19:28 -03:00
// @Group: STAT
// @Path: ../libraries/AP_Stats/AP_Stats.cpp
AP_SUBGROUPINFO ( stats , " STAT " , 1 , ParametersG2 , AP_Stats ) ,
2018-02-28 08:23:09 -04:00
# endif
2017-02-28 02:07:59 -04:00
// @Param: SYSID_ENFORCE
2016-11-21 11:06:25 -04:00
// @DisplayName: GCS sysid enforcement
// @Description: This controls whether packets from other than the expected GCS system ID will be accepted
// @Values: 0:NotEnforced,1:Enforced
// @User: Advanced
AP_GROUPINFO ( " SYSID_ENFORCE " , 2 , ParametersG2 , sysid_enforce , 0 ) ,
2017-01-06 06:31:10 -04:00
// @Group: SERVO
2017-02-05 22:15:51 -04:00
// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp
2017-01-06 06:31:10 -04:00
AP_SUBGROUPINFO ( servo_channels , " SERVO " , 3 , ParametersG2 , SRV_Channels ) ,
// @Group: RC
2018-08-03 23:28:09 -03:00
// @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h
2018-05-07 23:35:08 -03:00
AP_SUBGROUPINFO ( rc_channels , " RC " , 4 , ParametersG2 , RC_Channels_Rover ) ,
2017-01-30 10:21:55 -04:00
# if ADVANCED_FAILSAFE == ENABLED
// @Group: AFS_
// @Path: ../libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp
AP_SUBGROUPINFO ( afs , " AFS_ " , 5 , ParametersG2 , AP_AdvancedFailsafe ) ,
# endif
2017-04-03 17:46:12 -03:00
// @Group: BCN
// @Path: ../libraries/AP_Beacon/AP_Beacon.cpp
AP_SUBGROUPINFO ( beacon , " BCN " , 6 , ParametersG2 , AP_Beacon ) ,
2017-06-01 04:39:49 -03:00
// @Group: VISO
// @Path: ../libraries/AP_VisualOdom/AP_VisualOdom.cpp
AP_SUBGROUPINFO ( visual_odom , " VISO " , 7 , ParametersG2 , AP_VisualOdom ) ,
2017-07-06 00:06:20 -03:00
// @Group: MOT_
2017-07-15 18:47:11 -03:00
// @Path: AP_MotorsUGV.cpp
2017-07-06 00:06:20 -03:00
AP_SUBGROUPINFO ( motors , " MOT_ " , 8 , ParametersG2 , AP_MotorsUGV ) ,
2017-07-27 09:56:56 -03:00
// @Group: WENC
2017-07-11 23:02:51 -03:00
// @Path: ../libraries/AP_WheelEncoder/AP_WheelEncoder.cpp
2017-07-27 09:56:56 -03:00
AP_SUBGROUPINFO ( wheel_encoder , " WENC " , 9 , ParametersG2 , AP_WheelEncoder ) ,
2017-07-11 23:02:51 -03:00
2017-08-08 02:37:21 -03:00
// @Group: ATC
// @Path: ../libraries/APM_Control/AR_AttitudeControl.cpp
AP_SUBGROUPINFO ( attitude_control , " ATC " , 10 , ParametersG2 , AR_AttitudeControl ) ,
2017-08-10 05:29:21 -03:00
// @Param: TURN_RADIUS
// @DisplayName: Turn radius of vehicle
// @Description: Turn radius of vehicle in meters while at low speeds. Lower values produce tighter turns in steering mode
// @Units: m
// @Range: 0 10
// @Increment: 0.1
// @User: Standard
AP_GROUPINFO ( " TURN_RADIUS " , 11 , ParametersG2 , turn_radius , 0.9 ) ,
2017-11-28 02:59:13 -04:00
// @Param: ACRO_TURN_RATE
// @DisplayName: Acro mode turn rate maximum
// @Description: Acro mode turn rate maximum
// @Units: deg/s
// @Range: 0 360
// @Increment: 1
// @User: Standard
AP_GROUPINFO ( " ACRO_TURN_RATE " , 12 , ParametersG2 , acro_turn_rate , 180.0f ) ,
2017-11-29 21:58:11 -04:00
// @Group: SRTL_
// @Path: ../libraries/AP_SmartRTL/AP_SmartRTL.cpp
AP_SUBGROUPINFO ( smart_rtl , " SRTL_ " , 13 , ParametersG2 , AP_SmartRTL ) ,
2017-12-05 21:41:28 -04:00
// @Param: WP_SPEED
// @DisplayName: Waypoint speed default
// @Description: Waypoint speed default. If zero use CRUISE_SPEED.
// @Units: m/s
// @Range: 0 100
// @Increment: 0.1
// @User: Standard
AP_GROUPINFO ( " WP_SPEED " , 14 , ParametersG2 , wp_speed , 0.0f ) ,
// @Param: RTL_SPEED
// @DisplayName: Return-to-Launch speed default
// @Description: Return-to-Launch speed default. If zero use WP_SPEED or CRUISE_SPEED.
// @Units: m/s
// @Range: 0 100
// @Increment: 0.1
// @User: Standard
AP_GROUPINFO ( " RTL_SPEED " , 15 , ParametersG2 , rtl_speed , 0.0f ) ,
2017-12-06 22:37:42 -04:00
// @Param: FRAME_CLASS
// @DisplayName: Frame Class
// @Description: Frame Class
2018-06-05 05:56:46 -03:00
// @Values: 0:Undefined,1:Rover,2:Boat,3:BalanceBot
2017-12-06 22:37:42 -04:00
// @User: Standard
AP_GROUPINFO ( " FRAME_CLASS " , 16 , ParametersG2 , frame_class , 1 ) ,
2017-08-16 07:02:56 -03:00
// @Group: FENCE_
// @Path: ../libraries/AC_Fence/AC_Fence.cpp
AP_SUBGROUPINFO ( fence , " FENCE_ " , 17 , ParametersG2 , AC_Fence ) ,
2017-08-16 07:57:42 -03:00
// @Group: PRX
// @Path: ../libraries/AP_Proximity/AP_Proximity.cpp
AP_SUBGROUPINFO ( proximity , " PRX " , 18 , ParametersG2 , AP_Proximity ) ,
2017-12-12 02:12:16 -04:00
// @Group: AVOID_
// @Path: ../libraries/AC_Avoidance/AC_Avoid.cpp
AP_SUBGROUPINFO ( avoid , " AVOID_ " , 19 , ParametersG2 , AC_Avoid ) ,
2018-05-18 05:38:06 -03:00
// @Param: PIVOT_TURN_RATE
// @DisplayName: Pivot turn rate
// @Description: Desired pivot turn rate in deg/s.
// @Units: deg/s
// @Range: 0 360
// @Increment: 1
// @User: Standard
AP_GROUPINFO ( " PIVOT_TURN_RATE " , 20 , ParametersG2 , pivot_turn_rate , 90 ) ,
2018-06-20 08:11:58 -03:00
// @Param: BAL_PITCH_MAX
// @DisplayName: BalanceBot Maximum Pitch
// @Description: Pitch angle in degrees at 100% throttle
// @Units: deg
// @Range: 0 5
// @Increment: 0.1
// @User: Standard
2018-07-23 03:20:46 -03:00
AP_GROUPINFO ( " BAL_PITCH_MAX " , 21 , ParametersG2 , bal_pitch_max , 2 ) ,
2018-06-20 08:11:58 -03:00
2018-06-27 10:53:30 -03:00
// @Param: CRASH_ANGLE
// @DisplayName: Crash Angle
// @Description: Pitch/Roll angle limit in degrees for crash check. Zero disables check
2018-06-21 09:50:28 -03:00
// @Units: deg
// @Range: 0 60
2018-06-27 10:53:30 -03:00
// @Increment: 1
2018-06-21 09:50:28 -03:00
// @User: Standard
2018-06-27 10:53:30 -03:00
AP_GROUPINFO ( " CRASH_ANGLE " , 22 , ParametersG2 , crash_angle , 0 ) ,
2018-06-21 09:50:28 -03:00
2018-05-24 01:47:07 -03:00
// @Group: FOLL
// @Path: ../libraries/AP_Follow/AP_Follow.cpp
AP_SUBGROUPINFO ( follow , " FOLL " , 23 , ParametersG2 , AP_Follow ) ,
2018-06-21 09:50:28 -03:00
2018-05-31 06:26:07 -03:00
// @Param: FRAME_TYPE
// @DisplayName: Frame Type
// @Description: Frame Type
// @Values: 0:Undefined,1:Omni3,2:OmniX,3:OmniPlus
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO ( " FRAME_TYPE " , 24 , ParametersG2 , frame_type , 0 ) ,
2018-08-07 01:22:51 -03:00
// @Param: LOIT_TYPE
// @DisplayName: Loiter type
// @Description: Loiter behaviour when around next to a taget point
// @Values: 0:Reverse to target point,1:Always face bow to target point
// @User: Standard
AP_GROUPINFO ( " LOIT_TYPE " , 25 , ParametersG2 , loit_type , 0 ) ,
2018-06-08 06:22:55 -03:00
// @Group: SPRAYER_
// @Path: ../libraries/AC_Sprayer/AC_Sprayer.cpp
AP_SUBGROUPINFO ( sprayer , " SPRAY_ " , 26 , ParametersG2 , AC_Sprayer ) ,
2018-08-08 00:48:30 -03:00
// @Group: WRC
// @Path: ../libraries/AP_WheelEncoder/AP_WheelRateControl.cpp
AP_SUBGROUPINFO ( wheel_rate_control , " WRC " , 27 , ParametersG2 , AP_WheelRateControl ) ,
2018-08-29 22:00:56 -03:00
# if AP_RALLY == ENABLED
2018-08-29 21:54:12 -03:00
// @Group: RALLY_
// @Path: AP_Rally.cpp,../libraries/AP_Rally/AP_Rally.cpp
AP_SUBGROUPINFO ( rally , " RALLY_ " , 28 , ParametersG2 , AP_Rally_Rover ) ,
# endif
2018-07-02 04:21:37 -03:00
// @Param: SIMPLE_TYPE
// @DisplayName: Simple_Type
// @Description: Simple mode types
// @Values: 0:InitialHeading,1:CardinalDirections
// @User: Standard
// @RebootRequired: True
AP_GROUPINFO ( " SIMPLE_TYPE " , 29 , ParametersG2 , simple_type , 0 ) ,
2018-09-25 10:09:21 -03:00
// @Param: LOIT_RADIUS
// @DisplayName: Loiter radius
// @Description: Vehicle will drift when within this distance of the target position
// @Units: m
// @Range: 0 20
// @Increment: 1
// @User: Standard
AP_GROUPINFO ( " LOIT_RADIUS " , 30 , ParametersG2 , loit_radius , 2 ) ,
2018-09-25 10:09:47 -03:00
// @Group: WNDVN_
// @Path: ../libraries/AP_WindVane/AP_WindVane.cpp
AP_SUBGROUPINFO ( windvane , " WNDVN_ " , 31 , ParametersG2 , AP_WindVane ) ,
// @Param: SAIL_ANGLE_MIN
// @DisplayName: Sail min angle
// @Description: Mainsheet tight, angle between centerline and boom
// @Units: deg
// @Range: 0 90
// @Increment: 1
// @User: Standard
AP_GROUPINFO ( " SAIL_ANGLE_MIN " , 32 , ParametersG2 , sail_angle_min , 0 ) ,
// @Param: SAIL_ANGLE_MAX
// @DisplayName: Sail max angle
// @Description: Mainsheet loose, angle between centerline and boom
// @Units: deg
// @Range: 0 90
// @Increment: 1
// @User: Standard
AP_GROUPINFO ( " SAIL_ANGLE_MAX " , 33 , ParametersG2 , sail_angle_max , 90 ) ,
// @Param: SAIL_ANGLE_IDEAL
// @DisplayName: Sail ideal angle
// @Description: Ideal angle between sail and apparent wind
// @Units: deg
// @Range: 0 90
// @Increment: 1
// @User: Standard
AP_GROUPINFO ( " SAIL_ANGLE_IDEAL " , 34 , ParametersG2 , sail_angle_ideal , 25 ) ,
// @Param: SAIL_HEEL_MAX
// @DisplayName: Sailing maximum heel angle
// @Description: When in auto sail trim modes the heel will be limited to this value using PID control
// @Units: deg
// @Range: 0 90
// @Increment: 1
// @User: Standard
AP_GROUPINFO ( " SAIL_HEEL_MAX " , 35 , ParametersG2 , sail_heel_angle_max , 15 ) ,
2018-09-14 04:09:07 -03:00
// @Param: SAIL_NO_GO_ANGLE
// @DisplayName: Sailing no go zone angle
// @Description: The typical closest angle to the wind the vehicle will sail at. the vehicle will sail at this angle when going upwind
// @Units: deg
// @Range: 0 90
// @Increment: 1
// @User: Standard
AP_GROUPINFO ( " SAIL_NO_GO_ANGLE " , 36 , ParametersG2 , sail_no_go , 45 ) ,
// @Group: ARSPD
2018-11-01 02:28:45 -03:00
// @Path: ../libraries/AP_Airspeed/AP_Airspeed.cpp
2018-09-14 04:09:07 -03:00
AP_SUBGROUPINFO ( airspeed , " ARSPD " , 37 , ParametersG2 , AP_Airspeed ) ,
2016-10-25 22:37:08 -03:00
AP_GROUPEND
} ;
2018-08-12 02:00:48 -03:00
// These auxiliary channel param descriptions are here so that users of beta Mission Planner (which uses the master branch as its source of descriptions)
// can get them. These lines can be removed once Rover-3.6-beta testing begins or we improve the source of descriptions for GCSs.
//
// @Param: CH7_OPTION
// @DisplayName: Channel 7 option
// @Description: What to do use channel 7 for
// @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:Loiter
// @User: Standard
// @Param: AUX_CH
// @DisplayName: Auxiliary switch channel
// @Description: RC Channel to use for auxiliary functions including saving waypoints
// @User: Advanced
2016-10-25 22:37:08 -03:00
2017-01-06 06:31:10 -04:00
ParametersG2 : : ParametersG2 ( void )
2017-07-19 01:33:11 -03:00
:
2017-01-30 10:21:55 -04:00
# if ADVANCED_FAILSAFE == ENABLED
2018-05-05 05:28:48 -03:00
afs ( rover . mission , rover . gps ) ,
2017-01-30 10:21:55 -04:00
# endif
2017-07-19 01:33:11 -03:00
beacon ( rover . serial_manager ) ,
2017-08-08 02:37:21 -03:00
motors ( rover . ServoRelayEvents ) ,
2018-08-08 00:48:30 -03:00
wheel_rate_control ( wheel_encoder ) ,
2017-11-29 21:58:11 -04:00
attitude_control ( rover . ahrs ) ,
2018-04-02 08:17:47 -03:00
smart_rtl ( ) ,
2017-08-16 07:57:42 -03:00
fence ( rover . ahrs ) ,
2017-12-12 02:12:16 -04:00
proximity ( rover . serial_manager ) ,
2018-05-24 01:47:07 -03:00
avoid ( rover . ahrs , fence , rover . g2 . proximity , & rover . g2 . beacon ) ,
2018-08-29 21:54:12 -03:00
follow ( ) ,
2018-09-25 10:09:47 -03:00
rally ( rover . ahrs ) ,
2018-09-14 04:09:07 -03:00
windvane ( ) ,
airspeed ( )
2017-01-06 06:31:10 -04:00
{
AP_Param : : setup_object_defaults ( this , var_info ) ;
}
2016-10-25 22:37:08 -03:00
2013-10-02 03:07:28 -03:00
/*
This is a conversion table from old parameter values to new
parameter names . The startup code looks for saved values of the old
parameters and will copy them across to the new parameters if the
new parameter does not yet have a saved value . It then saves the new
value .
Note that this works even if the old parameter has been removed . It
relies on the old k_param index not being removed
The second column below is the index in the var_info [ ] table for the
old object . This should be zero for top level parameters .
*/
2015-10-25 14:03:46 -03:00
const AP_Param : : ConversionInfo conversion_table [ ] = {
2013-10-02 03:07:28 -03:00
{ Parameters : : k_param_battery_monitoring , 0 , AP_PARAM_INT8 , " BATT_MONITOR " } ,
{ Parameters : : k_param_battery_volt_pin , 0 , AP_PARAM_INT8 , " BATT_VOLT_PIN " } ,
{ Parameters : : k_param_battery_curr_pin , 0 , AP_PARAM_INT8 , " BATT_CURR_PIN " } ,
{ Parameters : : k_param_volt_div_ratio , 0 , AP_PARAM_FLOAT , " BATT_VOLT_MULT " } ,
{ Parameters : : k_param_curr_amp_per_volt , 0 , AP_PARAM_FLOAT , " BATT_AMP_PERVOLT " } ,
{ Parameters : : k_param_pack_capacity , 0 , AP_PARAM_INT32 , " BATT_CAPACITY " } ,
2015-01-28 00:56:36 -04:00
{ Parameters : : k_param_serial0_baud , 0 , AP_PARAM_INT16 , " SERIAL0_BAUD " } ,
{ Parameters : : k_param_serial1_baud , 0 , AP_PARAM_INT16 , " SERIAL1_BAUD " } ,
{ Parameters : : k_param_serial2_baud , 0 , AP_PARAM_INT16 , " SERIAL2_BAUD " } ,
2017-08-15 22:32:56 -03:00
{ Parameters : : k_param_throttle_min_old , 0 , AP_PARAM_INT8 , " MOT_THR_MIN " } ,
{ Parameters : : k_param_throttle_max_old , 0 , AP_PARAM_INT8 , " MOT_THR_MAX " } ,
2013-10-02 03:07:28 -03:00
} ;
2012-04-30 04:17:14 -03:00
2015-05-12 02:03:23 -03:00
void Rover : : load_parameters ( void )
2012-04-30 04:17:14 -03:00
{
2014-01-30 22:10:15 -04:00
if ( ! AP_Param : : check_var_info ( ) ) {
2017-08-11 00:49:03 -03:00
hal . console - > printf ( " Bad var table \n " ) ;
2015-11-19 23:04:16 -04:00
AP_HAL : : panic ( " Bad var table " ) ;
2014-01-30 22:10:15 -04:00
}
2016-12-20 09:30:04 -04:00
if ( ! g . format_version . load ( ) | |
g . format_version ! = Parameters : : k_format_version ) {
// erase all parameters
2017-08-11 00:49:03 -03:00
hal . console - > printf ( " Firmware change: erasing EEPROM... \n " ) ;
2016-12-20 09:30:04 -04:00
AP_Param : : erase_all ( ) ;
2012-04-30 04:17:14 -03:00
2016-12-20 09:30:04 -04:00
// save the current format version
g . format_version . set_and_save ( Parameters : : k_format_version ) ;
2017-08-11 00:49:03 -03:00
hal . console - > printf ( " done. \n " ) ;
2016-01-06 18:32:36 -04:00
}
2012-04-30 04:17:14 -03:00
2017-01-31 06:12:26 -04:00
const uint32_t before = micros ( ) ;
2016-01-06 18:32:36 -04:00
// Load all auto-loaded EEPROM variables
AP_Param : : load_all ( ) ;
2017-08-16 00:04:10 -03:00
AP_Param : : convert_old_parameters ( & conversion_table [ 0 ] , ARRAY_SIZE ( conversion_table ) ) ;
2016-12-20 09:30:04 -04:00
2017-02-07 19:47:46 -04:00
AP_Param : : set_frame_type_flags ( AP_PARAM_FRAME_ROVER ) ;
2017-01-31 05:46:32 -04:00
2017-01-08 21:43:57 -04:00
SRV_Channels : : set_default_function ( CH_1 , SRV_Channel : : k_steering ) ;
SRV_Channels : : set_default_function ( CH_3 , SRV_Channel : : k_throttle ) ;
2017-01-31 05:46:32 -04:00
2018-06-27 10:53:30 -03:00
if ( is_balancebot ( ) ) {
g2 . crash_angle . set_default ( 30 ) ;
}
2018-09-25 10:09:47 -03:00
// sailboat defaults
if ( g2 . motors . has_sail ( ) ) {
g2 . crash_angle . set_default ( 0 ) ;
g2 . loit_type . set_default ( 1 ) ;
g2 . loit_radius . set_default ( 5 ) ;
g . waypoint_overshoot . set_default ( 10 ) ;
}
2017-01-08 21:43:57 -04:00
const uint8_t old_rc_keys [ 14 ] = { Parameters : : k_param_rc_1_old , Parameters : : k_param_rc_2_old ,
Parameters : : k_param_rc_3_old , Parameters : : k_param_rc_4_old ,
Parameters : : k_param_rc_5_old , Parameters : : k_param_rc_6_old ,
Parameters : : k_param_rc_7_old , Parameters : : k_param_rc_8_old ,
Parameters : : k_param_rc_9_old , Parameters : : k_param_rc_10_old ,
Parameters : : k_param_rc_11_old , Parameters : : k_param_rc_12_old ,
Parameters : : k_param_rc_13_old , Parameters : : k_param_rc_14_old } ;
const uint16_t old_aux_chan_mask = 0x3FFA ;
SRV_Channels : : upgrade_parameters ( old_rc_keys , old_aux_chan_mask , & rcmap ) ;
2018-05-03 22:20:58 -03:00
hal . console - > printf ( " load_all took %uus \n " , unsigned ( micros ( ) - before ) ) ;
2018-05-08 09:19:03 -03:00
2013-09-09 06:55:11 -03:00
// set a more reasonable default NAVL1_PERIOD for rovers
2017-02-20 10:06:20 -04:00
L1_controller . set_default_period ( NAVL1_PERIOD ) ;
2018-05-08 09:19:03 -03:00
// configure safety switch to allow stopping the motors while armed
2018-08-01 20:46:59 -03:00
# if HAL_HAVE_SAFETY_SWITCH
2018-05-08 09:19:03 -03:00
AP_Param : : set_default_by_name ( " BRD_SAFETYOPTION " , AP_BoardConfig : : BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_OFF |
AP_BoardConfig : : BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_ON |
AP_BoardConfig : : BOARD_SAFETY_OPTION_BUTTON_ACTIVE_ARMED ) ;
# endif
2012-04-30 04:17:14 -03:00
}