2013-05-29 20:55:37 -03:00
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2012-04-30 04:17:14 -03:00
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 [ ] = {
2013-01-17 16:56:32 -04:00
GSCALAR ( format_version , " FORMAT_VERSION " , 1 ) ,
2012-08-06 22:24:20 -03:00
GSCALAR ( software_type , " SYSID_SW_TYPE " , Parameters : : k_software_type ) ,
2013-02-08 06:17:54 -04:00
// misc
2013-05-20 23:21:38 -03:00
// @Param: LOG_BITMASK
// @DisplayName: Log bitmask
// @Description: Two byte bitmap of log types to enable in dataflash
// @Values: 0:Disabled,3950:Default,4078:Default+IMU
// @User: Advanced
2013-02-08 06:17:54 -04:00
GSCALAR ( log_bitmask , " LOG_BITMASK " , DEFAULT_LOG_BITMASK ) ,
GSCALAR ( num_resets , " SYS_NUM_RESETS " , 0 ) ,
2013-06-03 04:55:22 -03:00
// @Param: RST_SWITCH_CH
// @DisplayName: Reset Switch Channel
// @Description: RC channel to use to reset to last flight mode after geofence takeover.
// @User: Advanced
2013-02-08 06:17:54 -04:00
GSCALAR ( reset_switch_chan , " RST_SWITCH_CH " , 0 ) ,
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.
2013-05-02 18:59:15 -03:00
// @Values: 0:MANUAL,2:LEARNING,3:STEERING,4:HOLD,10:AUTO,11:RTL,15:GUIDED
// @User: Advanced
GSCALAR ( initial_mode , " INITIAL_MODE " , MANUAL ) ,
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
2012-08-06 22:24:20 -03: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
// @Description: ID used in MAVLink protocol to identify the controlling ground station
2014-01-13 21:10:47 -04:00
// @Range: 1 255
2013-02-08 06:17:54 -04:00
// @User: Advanced
2012-08-06 22:24:20 -03:00
GSCALAR ( sysid_my_gcs , " SYSID_MYGCS " , 255 ) ,
2012-11-27 20:42:51 -04:00
2015-06-07 13:40:36 -03:00
# if CLI_ENABLED == ENABLED
// @Param: CLI_ENABLED
// @DisplayName: CLI Enable
// @Description: This enables/disables the checking for three carriage returns on telemetry links on startup to enter the diagnostics command line interface
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
GSCALAR ( cli_enabled , " CLI_ENABLED " , 0 ) ,
# endif
2012-11-27 20:42:51 -04:00
// @Param: TELEM_DELAY
// @DisplayName: Telemetry startup delay
// @Description: The amount of time (in seconds) to delay radio telemetry to prevent an Xbee bricking on power up
// @User: Standard
// @Units: seconds
// @Range: 0 10
// @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
// @Values: 0:None,1:Steering
// @Bitmask: 0:Steering
GSCALAR ( gcs_pid_mask , " GCS_PID_MASK " , 0 ) ,
2013-10-20 19:09:57 -03:00
2013-02-08 06:17:54 -04:00
// @Param: MAG_ENABLED
// @DisplayName: Magnetometer (compass) enabled
// @Description: This should be set to 1 if a compass is installed
// @User: Standard
2012-11-27 20:42:51 -04:00
// @Values: 0:Disabled,1:Enabled
2013-02-08 06:17:54 -04:00
GSCALAR ( compass_enabled , " MAG_ENABLE " , MAGNETOMETER ) ,
2013-03-21 19:38:25 -03:00
// @Param: AUTO_TRIGGER_PIN
// @DisplayName: Auto mode trigger pin
2013-06-01 18:55:38 -03:00
// @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.
2015-04-10 05:15:41 -03:00
// @Values: -1:Disabled, 0-8:APM TriggerPin, 50-55: Pixhawk TriggerPin
2013-03-21 19:38:25 -03:00
// @User: standard
GSCALAR ( auto_trigger_pin , " AUTO_TRIGGER_PIN " , - 1 ) ,
// @Param: AUTO_KICKSTART
// @DisplayName: Auto mode trigger kickstart acceleration
2013-03-21 21:22:02 -03:00
// @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
2013-03-21 19:38:25 -03:00
// @Range: 0 20
2013-03-21 21:22:02 -03:00
// @Increment: 0.1
2013-03-21 19:38:25 -03:00
// @User: standard
GSCALAR ( auto_kickstart , " AUTO_KICKSTART " , 0.0f ) ,
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
2013-02-08 06:17:54 -04:00
GSCALAR ( speed_cruise , " CRUISE_SPEED " , 5 ) ,
2013-02-21 17:38:13 -04:00
// @Param: SPEED_TURN_GAIN
// @DisplayName: Target speed reduction while turning
// @Description: The percentage to reduce the throttle while turning. If this is 100% then the target speed is not reduced while turning. If this is 50% then the target speed is reduced in proportion to the turn rate, with a reduction of 50% when the steering is maximally deflected.
// @Units: percent
// @Range: 0 100
// @Increment: 1
// @User: Standard
GSCALAR ( speed_turn_gain , " SPEED_TURN_GAIN " , 50 ) ,
// @Param: SPEED_TURN_DIST
// @DisplayName: Distance to turn to start reducing speed
// @Description: The distance to the next turn at which the rover reduces its target speed by the SPEED_TURN_GAIN
// @Units: meters
// @Range: 0 100
// @Increment: 0.1
// @User: Standard
GSCALAR ( speed_turn_dist , " SPEED_TURN_DIST " , 2.0f ) ,
2014-03-30 18:44:19 -03:00
// @Param: BRAKING_PERCENT
// @DisplayName: Percentage braking to apply
// @Description: The maximum reverse throttle braking percentage to apply when cornering
// @Units: percent
// @Range: 0 100
// @Increment: 1
// @User: Standard
GSCALAR ( braking_percent , " BRAKING_PERCENT " , 0 ) ,
2014-04-06 19:42:54 -03:00
// @Param: BRAKING_SPEEDERR
// @DisplayName: Speed error at which to apply braking
// @Description: The amount of overspeed error at which to start applying braking
// @Units: m/s
// @Range: 0 100
// @Increment: 1
// @User: Standard
GSCALAR ( braking_speederr , " BRAKING_SPEEDERR " , 3 ) ,
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.
// @Units: degrees
// @Range: 0 360
// @Increment: 1
// @User: Standard
GSCALAR ( pivot_turn_angle , " PIVOT_TURN_ANGLE " , 30 ) ,
2013-02-08 06:17:54 -04:00
// @Param: CH7_OPTION
// @DisplayName: Channel 7 option
// @Description: What to do use channel 7 for
// @Values: 0:Nothing,1:LearnWaypoint
// @User: Standard
GSCALAR ( ch7_option , " CH7_OPTION " , CH7_OPTION ) ,
2013-06-03 04:55:22 -03:00
// @Group: RC1_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
2013-06-03 06:33:59 -03:00
GGROUP ( rc_1 , " RC1_ " , RC_Channel ) ,
2013-06-03 04:55:22 -03:00
// @Group: RC2_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
2013-02-08 06:17:54 -04:00
GGROUP ( rc_2 , " RC2_ " , RC_Channel_aux ) ,
2013-06-03 04:55:22 -03:00
// @Group: RC3_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
2013-06-03 06:33:59 -03:00
GGROUP ( rc_3 , " RC3_ " , RC_Channel ) ,
2013-06-03 04:55:22 -03:00
// @Group: RC4_
2014-01-20 05:11:08 -04:00
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
2013-02-08 06:17:54 -04:00
GGROUP ( rc_4 , " RC4_ " , RC_Channel_aux ) ,
2013-06-03 04:55:22 -03:00
// @Group: RC5_
2014-01-20 05:11:08 -04:00
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
2013-02-08 06:17:54 -04:00
GGROUP ( rc_5 , " RC5_ " , RC_Channel_aux ) ,
2013-06-03 04:55:22 -03:00
// @Group: RC6_
2014-01-20 05:11:08 -04:00
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
2013-02-08 06:17:54 -04:00
GGROUP ( rc_6 , " RC6_ " , RC_Channel_aux ) ,
2013-06-03 04:55:22 -03:00
// @Group: RC7_
2014-01-20 05:11:08 -04:00
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
2013-02-08 06:17:54 -04:00
GGROUP ( rc_7 , " RC7_ " , RC_Channel_aux ) ,
2013-06-03 04:55:22 -03:00
// @Group: RC8_
2014-01-20 05:11:08 -04:00
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
2013-02-08 06:17:54 -04:00
GGROUP ( rc_8 , " RC8_ " , RC_Channel_aux ) ,
2012-04-30 04:17:14 -03:00
2014-03-31 14:58:48 -03:00
# if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
2013-07-14 20:57:00 -03:00
// @Group: RC9_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP ( rc_9 , " RC9_ " , RC_Channel_aux ) ,
// @Group: RC10_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP ( rc_10 , " RC10_ " , RC_Channel_aux ) ,
// @Group: RC11_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP ( rc_11 , " RC11_ " , RC_Channel_aux ) ,
// @Group: RC12_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP ( rc_12 , " RC12_ " , RC_Channel_aux ) ,
2014-03-25 00:41:38 -03:00
// @Group: RC13_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP ( rc_13 , " RC13_ " , RC_Channel_aux ) ,
// @Group: RC14_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP ( rc_14 , " RC14_ " , RC_Channel_aux ) ,
2013-07-14 20:57:00 -03:00
# endif
2012-11-27 20:42:51 -04:00
// @Param: THR_MIN
// @DisplayName: Minimum Throttle
2013-02-07 18:21:22 -04:00
// @Description: The minimum throttle setting to which the autopilot will apply. This is mostly useful for rovers with internal combustion motors, to prevent the motor from cutting out in auto mode.
2012-11-27 20:42:51 -04:00
// @Units: Percent
// @Range: 0 100
// @Increment: 1
// @User: Standard
2012-08-06 22:24:20 -03:00
GSCALAR ( throttle_min , " THR_MIN " , THROTTLE_MIN ) ,
2012-11-27 20:42:51 -04:00
// @Param: THR_MAX
// @DisplayName: Maximum Throttle
2013-02-21 17:38:13 -04:00
// @Description: The maximum throttle setting to which the autopilot will apply. This can be used to prevent overheating a ESC or motor on an electric rover.
2012-11-27 20:42:51 -04:00
// @Units: Percent
// @Range: 0 100
// @Increment: 1
// @User: Standard
2012-08-06 22:24:20 -03:00
GSCALAR ( throttle_max , " THR_MAX " , THROTTLE_MAX ) ,
2012-11-27 20:42:51 -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.
2013-02-08 06:17:54 -04:00
// @Units: Percent
// @Range: 0 100
// @Increment: 1
// @User: Standard
GSCALAR ( throttle_cruise , " CRUISE_THROTTLE " , 50 ) ,
2012-11-27 20:42:51 -04:00
// @Param: THR_SLEWRATE
2012-12-03 20:38:29 -04:00
// @DisplayName: Throttle slew rate
2014-07-27 08:25:55 -03:00
// @Description: maximum percentage change in throttle per second. A setting of 10 means to not change the throttle by more than 10% of the full throttle range in one second. A value of zero means no limit. A value of 100 means the throttle can change over its full range in one second. Note that for some NiMH powered rovers setting a lower value like 40 or 50 may be worthwhile as the sudden current demand on the battery of a big rise in throttle may cause a brownout.
2012-11-27 20:42:51 -04:00
// @Units: Percent
// @Range: 0 100
// @Increment: 1
// @User: Standard
2014-07-27 08:25:55 -03:00
GSCALAR ( throttle_slewrate , " THR_SLEWRATE " , 100 ) ,
2012-11-27 20:42:51 -04:00
2013-03-14 21:04:33 -03:00
// @Param: SKID_STEER_OUT
// @DisplayName: Skid steering output
// @Description: Set this to 1 for skid steering controlled rovers (tank track style). When enabled, servo1 is used for the left track control, servo3 is used for right track control
// @Values: 0:Disabled, 1:SkidSteeringOutput
// @User: Standard
GSCALAR ( skid_steer_out , " SKID_STEER_OUT " , 0 ) ,
// @Param: SKID_STEER_IN
// @DisplayName: Skid steering input
// @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
2013-03-29 08:46:58 -03:00
// @Values: 0:Disabled, 1:SkidSteeringInput
2013-03-14 21:04:33 -03:00
// @User: Standard
GSCALAR ( skid_steer_in , " SKID_STEER_IN " , 0 ) ,
2013-02-08 06:17:54 -04:00
// @Param: FS_ACTION
// @DisplayName: Failsafe Action
// @Description: What to do on a failsafe event
2013-03-28 20:25:53 -03:00
// @Values: 0:Nothing,1:RTL,2:HOLD
2013-02-08 06:17:54 -04:00
// @User: Standard
2013-03-28 21:34:42 -03:00
GSCALAR ( fs_action , " FS_ACTION " , 2 ) ,
2013-02-08 06:17:54 -04:00
// @Param: FS_TIMEOUT
// @DisplayName: Failsafe timeout
// @Description: How long a failsafe event need to happen for before we trigger the failsafe action
// @Units: seconds
// @User: Standard
2013-03-28 20:25:53 -03:00
GSCALAR ( fs_timeout , " FS_TIMEOUT " , 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
2013-03-28 21:34:42 -03: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
2015-08-17 18:25:58 -03:00
// @Description: The PWM level on channel 3 below which throttle failsafe triggers.
2013-06-18 03:57:11 -03:00
// @Range: 925 1100
// @Increment: 1
2012-11-27 20:42:51 -04:00
// @User: Standard
2013-03-28 21:34:42 -03: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
2013-02-08 06:17:54 -04:00
GSCALAR ( fs_gcs_enabled , " FS_GCS_ENABLE " , 0 ) ,
2014-07-16 16:18:10 -03:00
// @Param: RNGFND_TRIGGR_CM
// @DisplayName: Rangefinder trigger distance
// @Description: The distance from an obstacle in centimeters at which the rangefinder triggers a turn to avoid the obstacle
2013-02-28 16:15:09 -04:00
// @Units: centimeters
// @Range: 0 1000
// @Increment: 1
// @User: Standard
2014-07-16 16:18:10 -03:00
GSCALAR ( sonar_trigger_cm , " RNGFND_TRIGGR_CM " , 100 ) ,
2013-02-28 16:15:09 -04:00
2014-07-16 16:18:10 -03:00
// @Param: RNGFND_TURN_ANGL
// @DisplayName: Rangefinder trigger angle
// @Description: The course deviation in degrees to apply while avoiding an obstacle detected with the rangefinder. A positive number means to turn right, and a negative angle means to turn left.
2013-02-28 16:15:09 -04:00
// @Units: centimeters
2013-03-01 07:32:57 -04:00
// @Range: -45 45
2013-02-28 16:15:09 -04:00
// @Increment: 1
// @User: Standard
2014-07-16 16:18:10 -03:00
GSCALAR ( sonar_turn_angle , " RNGFND_TURN_ANGL " , 45 ) ,
2013-02-28 16:15:09 -04:00
2014-07-16 16:18:10 -03:00
// @Param: RNGFND_TURN_TIME
// @DisplayName: Rangefinder turn time
// @Description: The amount of time in seconds to apply the RNGFND_TURN_ANGL after detecting an obstacle.
2013-02-28 16:15:09 -04:00
// @Units: seconds
// @Range: 0 100
// @Increment: 0.1
// @User: Standard
2014-07-16 16:18:10 -03:00
GSCALAR ( sonar_turn_time , " RNGFND_TURN_TIME " , 1.0f ) ,
2013-02-28 16:15:09 -04:00
2014-07-16 16:18:10 -03:00
// @Param: RNGFND_DEBOUNCE
// @DisplayName: Rangefinder debounce count
// @Description: The number of 50Hz rangefinder hits needed to trigger an obstacle avoidance event. If you get a lot of false sonar 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
// @User: Standard
2014-07-16 16:18:10 -03:00
GSCALAR ( sonar_debounce , " RNGFND_DEBOUNCE " , 2 ) ,
2013-03-28 20:49:08 -03:00
2013-06-30 21:10:38 -03:00
// @Param: LEARN_CH
// @DisplayName: Learning channel
// @Description: RC Channel to use for learning waypoints
// @User: Advanced
GSCALAR ( learn_channel , " LEARN_CH " , 7 ) ,
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
2013-02-07 18:21:22 -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
2013-03-28 18:53:20 -03:00
// @Values: 0:Manual,2:LEARNING,3:STEERING,4:HOLD,10:Auto,11:RTL,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)
2013-02-07 18:21:22 -04:00
GSCALAR ( mode1 , " MODE1 " , MODE_1 ) ,
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)
2013-03-28 18:53:20 -03:00
// @Values: 0:Manual,2:LEARNING,3:STEERING,4:HOLD,10:Auto,11:RTL,15:Guided
2012-11-27 20:42:51 -04:00
// @User: Standard
2013-02-07 18:21:22 -04:00
GSCALAR ( mode2 , " MODE2 " , MODE_2 ) ,
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)
2013-03-28 18:53:20 -03:00
// @Values: 0:Manual,2:LEARNING,3:STEERING,4:HOLD,10:Auto,11:RTL,15:Guided
2012-11-27 20:42:51 -04:00
// @User: Standard
2013-02-07 18:21:22 -04:00
GSCALAR ( mode3 , " MODE3 " , MODE_3 ) ,
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)
2013-03-28 18:53:20 -03:00
// @Values: 0:Manual,2:LEARNING,3:STEERING,4:HOLD,10:Auto,11:RTL,15:Guided
2012-11-27 20:42:51 -04:00
// @User: Standard
2013-02-07 18:21:22 -04:00
GSCALAR ( mode4 , " MODE4 " , MODE_4 ) ,
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)
2013-03-28 18:53:20 -03:00
// @Values: 0:Manual,2:LEARNING,3:STEERING,4:HOLD,10:Auto,11:RTL,15:Guided
2012-11-27 20:42:51 -04:00
// @User: Standard
2013-02-07 18:21:22 -04:00
GSCALAR ( mode5 , " MODE5 " , MODE_5 ) ,
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)
2013-03-28 18:53:20 -03:00
// @Values: 0:Manual,2:LEARNING,3:STEERING,4:HOLD,10:Auto,11:RTL,15:Guided
2012-11-27 20:42:51 -04:00
// @User: Standard
2013-02-07 18:21:22 -04:00
GSCALAR ( mode6 , " MODE6 " , MODE_6 ) ,
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.
// @Units: meters
// @Range: 0 1000
// @Increment: 0.1
2012-12-18 07:44:12 -04:00
// @User: Standard
2013-02-08 06:17:54 -04:00
GSCALAR ( waypoint_radius , " WP_RADIUS " , 2.0f ) ,
2012-04-30 04:17:14 -03:00
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
// @Range: 0.2 10
// @Increment: 0.1
// @User: Standard
GSCALAR ( turn_max_g , " TURN_MAX_G " , 2.0f ) ,
2013-09-08 21:18:31 -03:00
// @Group: STEER2SRV_
// @Path: ../libraries/APM_Control/AP_SteerController.cpp
GOBJECT ( steerController , " STEER2SRV_ " , AP_SteerController ) ,
2013-02-07 18:21:22 -04:00
GGROUP ( pidSpeedThrottle , " SPEED2THR_ " , PID ) ,
2012-04-30 04:17:14 -03:00
// variables not in the g class which contain EEPROM saved variables
2013-06-03 04:55:22 -03:00
// @Group: COMPASS_
// @Path: ../libraries/AP_Compass/Compass.cpp
2012-04-30 04:17:14 -03: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
2013-11-23 06:57:26 -04:00
GOBJECTN ( gcs [ 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
2013-11-23 06:57:26 -04:00
GOBJECTN ( gcs [ 1 ] , gcs1 , " SR1_ " , GCS_MAVLINK ) ,
// @Group: SR2_
2015-05-20 22:42:59 -03:00
// @Path: GCS_Mavlink.cpp
2013-11-23 06:57:26 -04:00
GOBJECTN ( gcs [ 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
2015-05-15 01:24:59 -03:00
GOBJECTN ( gcs [ 3 ] , gcs3 , " SR3_ " , GCS_MAVLINK ) ,
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
2014-07-16 16:18:10 -03:00
GOBJECT ( sonar , " 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-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 ) ,
2014-03-31 16:18:27 -03:00
// GPS driver
// @Group: GPS_
// @Path: ../libraries/AP_GPS/AP_GPS.cpp
GOBJECT ( gps , " GPS_ " , AP_GPS ) ,
2014-02-21 00:51:34 -04:00
# if AP_AHRS_NAVEKF_AVAILABLE
// @Group: EKF_
// @Path: ../libraries/AP_NavEKF/AP_NavEKF.cpp
2015-06-01 03:17:15 -03:00
GOBJECTN ( EKF , NavEKF , " EKF_ " , NavEKF ) ,
2015-09-21 02:27:49 -03:00
// @Group: EK2_
// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp
GOBJECTN ( EKF2 , NavEKF2 , " EK2_ " , NavEKF2 ) ,
2014-02-21 00:51:34 -04:00
# endif
2014-03-10 05:42:44 -03:00
// @Group: MIS_
// @Path: ../libraries/AP_Mission/AP_Mission.cpp
GOBJECT ( mission , " MIS_ " , AP_Mission ) ,
2015-08-28 03:00:12 -03:00
// @Group: RSSI_
// @Path: ../libraries/AP_RSSI/AP_RSSI.cpp
GOBJECT ( rssi , " RSSI_ " , AP_RSSI ) ,
2014-03-10 05:42:44 -03:00
2012-08-06 22:24:20 -03:00
AP_VAREND
2012-04-30 04:17:14 -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 " } ,
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 ( ) ) {
2015-10-25 17:10:41 -03:00
cliSerial - > printf ( " Bad var table \n " ) ;
2015-10-24 18:45:41 -03:00
hal . scheduler - > panic ( " Bad var table " ) ;
2014-01-30 22:10:15 -04:00
}
2012-04-30 04:17:14 -03:00
if ( ! g . format_version . load ( ) | |
g . format_version ! = Parameters : : k_format_version ) {
// erase all parameters
2015-10-25 17:10:41 -03:00
cliSerial - > printf ( " Firmware change: erasing EEPROM... \n " ) ;
2012-04-30 04:17:14 -03:00
AP_Param : : erase_all ( ) ;
// save the current format version
g . format_version . set_and_save ( Parameters : : k_format_version ) ;
2015-10-25 16:50:51 -03:00
cliSerial - > println ( " done. " ) ;
2012-04-30 04:17:14 -03:00
} else {
unsigned long before = micros ( ) ;
// Load all auto-loaded EEPROM variables
AP_Param : : load_all ( ) ;
2015-10-25 17:10:41 -03:00
cliSerial - > printf ( " load_all took %luus \n " , micros ( ) - before ) ;
2012-04-30 04:17:14 -03:00
}
2013-09-09 06:55:11 -03:00
// set a more reasonable default NAVL1_PERIOD for rovers
2013-09-23 18:37:24 -03:00
L1_controller . set_default_period ( 8 ) ;
2012-04-30 04:17:14 -03:00
}