mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: Parameters.cpp correct whitespace, remove tabs
This commit is contained in:
parent
5858c84f83
commit
70d0997b73
@ -14,14 +14,14 @@ const AP_Param::Info Rover::var_info[] = {
|
||||
// @DisplayName: Eeprom format version number
|
||||
// @Description: This value is incremented when changes are made to the eeprom format
|
||||
// @User: Advanced
|
||||
GSCALAR(format_version, "FORMAT_VERSION", 1),
|
||||
GSCALAR(format_version, "FORMAT_VERSION", 1),
|
||||
|
||||
// @Param: SYSID_SW_TYPE
|
||||
// @DisplayName: Software Type
|
||||
// @Description: This is used by the ground station to recognise the software type (eg ArduPlane vs ArduCopter)
|
||||
// @User: Advanced
|
||||
// @ReadOnly: True
|
||||
GSCALAR(software_type, "SYSID_SW_TYPE", Parameters::k_software_type),
|
||||
GSCALAR(software_type, "SYSID_SW_TYPE", Parameters::k_software_type),
|
||||
|
||||
// @Param: LOG_BITMASK
|
||||
// @DisplayName: Log bitmask
|
||||
@ -29,40 +29,40 @@ const AP_Param::Info Rover::var_info[] = {
|
||||
// @Values: 0:Disabled,5190:APM2-Default,65535:PX4/Pixhawk-Default
|
||||
// @Bitmask: 0:ATTITUDE_FAST,1:ATTITUDE_MED,2:GPS,3:PM,4:CTUN,5:NTUN,6:MODE,7:IMU,8:CMD,9:CURRENT,10:COMPASS,11:TECS,12:CAMERA,13:RC,14:SONAR,15:ARM/DISARM,19:IMU_RAW
|
||||
// @User: Advanced
|
||||
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),
|
||||
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),
|
||||
|
||||
// @Param: SYS_NUM_RESETS
|
||||
// @DisplayName: Num Resets
|
||||
// @Description: Number of APM board resets
|
||||
// @User: Advanced
|
||||
GSCALAR(num_resets, "SYS_NUM_RESETS", 0),
|
||||
GSCALAR(num_resets, "SYS_NUM_RESETS", 0),
|
||||
|
||||
// @Param: RST_SWITCH_CH
|
||||
// @DisplayName: Reset Switch Channel
|
||||
// @Description: RC channel to use to reset to last flight mode after geofence takeover.
|
||||
// @Description: RC channel to use to reset to last flight mode after geofence takeover.
|
||||
// @User: Advanced
|
||||
GSCALAR(reset_switch_chan, "RST_SWITCH_CH", 0),
|
||||
GSCALAR(reset_switch_chan, "RST_SWITCH_CH", 0),
|
||||
|
||||
// @Param: INITIAL_MODE
|
||||
// @DisplayName: Initial driving mode
|
||||
// @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.
|
||||
// @Values: 0:MANUAL,2:LEARNING,3:STEERING,4:HOLD,10:AUTO,11:RTL,15:GUIDED
|
||||
// @User: Advanced
|
||||
GSCALAR(initial_mode, "INITIAL_MODE", MANUAL),
|
||||
GSCALAR(initial_mode, "INITIAL_MODE", MANUAL),
|
||||
|
||||
// @Param: SYSID_THIS_MAV
|
||||
// @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
|
||||
// @Range: 1 255
|
||||
// @User: Advanced
|
||||
GSCALAR(sysid_this_mav, "SYSID_THISMAV", MAV_SYSTEM_ID),
|
||||
GSCALAR(sysid_this_mav, "SYSID_THISMAV", MAV_SYSTEM_ID),
|
||||
|
||||
// @Param: SYSID_MYGCS
|
||||
// @DisplayName: MAVLink ground station ID
|
||||
// @Description: The identifier of the ground station in the MAVLink protocol. Don't change this unless you also modify the ground station to match.
|
||||
// @Range: 1 255
|
||||
// @User: Advanced
|
||||
GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),
|
||||
GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255),
|
||||
|
||||
#if CLI_ENABLED == ENABLED
|
||||
// @Param: CLI_ENABLED
|
||||
@ -95,23 +95,23 @@ const AP_Param::Info Rover::var_info[] = {
|
||||
// @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.
|
||||
// @User: Standard
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
GSCALAR(compass_enabled, "MAG_ENABLE", MAGNETOMETER),
|
||||
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.
|
||||
// @Values: -1:Disabled, 0-8:APM TriggerPin, 50-55: Pixhawk TriggerPin
|
||||
// @User: standard
|
||||
GSCALAR(auto_trigger_pin, "AUTO_TRIGGER_PIN", -1),
|
||||
// @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.
|
||||
// @Values: -1:Disabled, 0-8:APM TriggerPin, 50-55: Pixhawk TriggerPin
|
||||
// @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),
|
||||
// @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),
|
||||
|
||||
// @Param: CRUISE_SPEED
|
||||
// @DisplayName: Target cruise speed in auto modes
|
||||
@ -120,7 +120,7 @@ const AP_Param::Info Rover::var_info[] = {
|
||||
// @Range: 0 100
|
||||
// @Increment: 0.1
|
||||
// @User: Standard
|
||||
GSCALAR(speed_cruise, "CRUISE_SPEED", SPEED_CRUISE),
|
||||
GSCALAR(speed_cruise, "CRUISE_SPEED", SPEED_CRUISE),
|
||||
|
||||
// @Param: SPEED_TURN_GAIN
|
||||
// @DisplayName: Target speed reduction while turning
|
||||
@ -129,7 +129,7 @@ const AP_Param::Info Rover::var_info[] = {
|
||||
// @Range: 0 100
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
GSCALAR(speed_turn_gain, "SPEED_TURN_GAIN", 50),
|
||||
GSCALAR(speed_turn_gain, "SPEED_TURN_GAIN", 50),
|
||||
|
||||
// @Param: SPEED_TURN_DIST
|
||||
// @DisplayName: Distance to turn to start reducing speed
|
||||
@ -138,7 +138,7 @@ const AP_Param::Info Rover::var_info[] = {
|
||||
// @Range: 0 100
|
||||
// @Increment: 0.1
|
||||
// @User: Standard
|
||||
GSCALAR(speed_turn_dist, "SPEED_TURN_DIST", 2.0f),
|
||||
GSCALAR(speed_turn_dist, "SPEED_TURN_DIST", 2.0f),
|
||||
|
||||
// @Param: BRAKING_PERCENT
|
||||
// @DisplayName: Percentage braking to apply
|
||||
@ -147,7 +147,7 @@ const AP_Param::Info Rover::var_info[] = {
|
||||
// @Range: 0 100
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
GSCALAR(braking_percent, "BRAKING_PERCENT", 0),
|
||||
GSCALAR(braking_percent, "BRAKING_PERCENT", 0),
|
||||
|
||||
// @Param: BRAKING_SPEEDERR
|
||||
// @DisplayName: Speed error at which to apply braking
|
||||
@ -156,7 +156,7 @@ const AP_Param::Info Rover::var_info[] = {
|
||||
// @Range: 0 100
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
GSCALAR(braking_speederr, "BRAKING_SPEEDERR", 3),
|
||||
GSCALAR(braking_speederr, "BRAKING_SPEEDERR", 3),
|
||||
|
||||
// @Param: PIVOT_TURN_ANGLE
|
||||
// @DisplayName: Pivot turn angle
|
||||
@ -165,46 +165,46 @@ const AP_Param::Info Rover::var_info[] = {
|
||||
// @Range: 0 360
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
GSCALAR(pivot_turn_angle, "PIVOT_TURN_ANGLE", 30),
|
||||
GSCALAR(pivot_turn_angle, "PIVOT_TURN_ANGLE", 30),
|
||||
|
||||
// @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),
|
||||
GSCALAR(ch7_option, "CH7_OPTION", CH7_OPTION),
|
||||
|
||||
// @Group: RC1_
|
||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
|
||||
GGROUP(rc_1, "RC1_", RC_Channel),
|
||||
GGROUP(rc_1, "RC1_", RC_Channel),
|
||||
|
||||
// @Group: RC2_
|
||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
|
||||
GGROUP(rc_2, "RC2_", RC_Channel_aux),
|
||||
GGROUP(rc_2, "RC2_", RC_Channel_aux),
|
||||
|
||||
// @Group: RC3_
|
||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
|
||||
GGROUP(rc_3, "RC3_", RC_Channel),
|
||||
GGROUP(rc_3, "RC3_", RC_Channel),
|
||||
|
||||
// @Group: RC4_
|
||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
||||
GGROUP(rc_4, "RC4_", RC_Channel_aux),
|
||||
GGROUP(rc_4, "RC4_", RC_Channel_aux),
|
||||
|
||||
// @Group: RC5_
|
||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
||||
GGROUP(rc_5, "RC5_", RC_Channel_aux),
|
||||
GGROUP(rc_5, "RC5_", RC_Channel_aux),
|
||||
|
||||
// @Group: RC6_
|
||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
||||
GGROUP(rc_6, "RC6_", RC_Channel_aux),
|
||||
GGROUP(rc_6, "RC6_", RC_Channel_aux),
|
||||
|
||||
// @Group: RC7_
|
||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
||||
GGROUP(rc_7, "RC7_", RC_Channel_aux),
|
||||
GGROUP(rc_7, "RC7_", RC_Channel_aux),
|
||||
|
||||
// @Group: RC8_
|
||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
||||
GGROUP(rc_8, "RC8_", RC_Channel_aux),
|
||||
GGROUP(rc_8, "RC8_", RC_Channel_aux),
|
||||
|
||||
// @Group: RC9_
|
||||
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
||||
@ -237,7 +237,7 @@ const AP_Param::Info Rover::var_info[] = {
|
||||
// @Range: 0 100
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
GSCALAR(throttle_min, "THR_MIN", THROTTLE_MIN),
|
||||
GSCALAR(throttle_min, "THR_MIN", THROTTLE_MIN),
|
||||
|
||||
// @Param: THR_MAX
|
||||
// @DisplayName: Maximum Throttle
|
||||
@ -246,7 +246,7 @@ const AP_Param::Info Rover::var_info[] = {
|
||||
// @Range: 0 100
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
GSCALAR(throttle_max, "THR_MAX", THROTTLE_MAX),
|
||||
GSCALAR(throttle_max, "THR_MAX", THROTTLE_MAX),
|
||||
|
||||
// @Param: CRUISE_THROTTLE
|
||||
// @DisplayName: Base throttle percentage in auto
|
||||
@ -255,7 +255,7 @@ const AP_Param::Info Rover::var_info[] = {
|
||||
// @Range: 0 100
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
GSCALAR(throttle_cruise, "CRUISE_THROTTLE", 50),
|
||||
GSCALAR(throttle_cruise, "CRUISE_THROTTLE", 50),
|
||||
|
||||
// @Param: THR_SLEWRATE
|
||||
// @DisplayName: Throttle slew rate
|
||||
@ -264,42 +264,42 @@ const AP_Param::Info Rover::var_info[] = {
|
||||
// @Range: 0 100
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
GSCALAR(throttle_slewrate, "THR_SLEWRATE", 100),
|
||||
GSCALAR(throttle_slewrate, "THR_SLEWRATE", 100),
|
||||
|
||||
// @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),
|
||||
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
|
||||
// @Values: 0:Disabled, 1:SkidSteeringInput
|
||||
// @User: Standard
|
||||
GSCALAR(skid_steer_in, "SKID_STEER_IN", 0),
|
||||
GSCALAR(skid_steer_in, "SKID_STEER_IN", 0),
|
||||
|
||||
// @Param: FS_ACTION
|
||||
// @DisplayName: Failsafe Action
|
||||
// @Description: What to do on a failsafe event
|
||||
// @Values: 0:Nothing,1:RTL,2:HOLD
|
||||
// @User: Standard
|
||||
GSCALAR(fs_action, "FS_ACTION", 2),
|
||||
GSCALAR(fs_action, "FS_ACTION", 2),
|
||||
|
||||
// @Param: FS_TIMEOUT
|
||||
// @DisplayName: Failsafe timeout
|
||||
// @Description: How long a failsafe event need to happen for before we trigger the failsafe action
|
||||
// @Units: seconds
|
||||
// @Units: seconds
|
||||
// @User: Standard
|
||||
GSCALAR(fs_timeout, "FS_TIMEOUT", 5),
|
||||
GSCALAR(fs_timeout, "FS_TIMEOUT", 5),
|
||||
|
||||
// @Param: FS_THR_ENABLE
|
||||
// @DisplayName: Throttle Failsafe Enable
|
||||
// @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.
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
// @User: Standard
|
||||
GSCALAR(fs_throttle_enabled, "FS_THR_ENABLE", 1),
|
||||
GSCALAR(fs_throttle_enabled, "FS_THR_ENABLE", 1),
|
||||
|
||||
// @Param: FS_THR_VALUE
|
||||
// @DisplayName: Throttle Failsafe Value
|
||||
@ -307,14 +307,14 @@ const AP_Param::Info Rover::var_info[] = {
|
||||
// @Range: 925 1100
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
GSCALAR(fs_throttle_value, "FS_THR_VALUE", 910),
|
||||
GSCALAR(fs_throttle_value, "FS_THR_VALUE", 910),
|
||||
|
||||
// @Param: FS_GCS_ENABLE
|
||||
// @DisplayName: GCS failsafe enable
|
||||
// @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.
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
// @User: Standard
|
||||
GSCALAR(fs_gcs_enabled, "FS_GCS_ENABLE", 0),
|
||||
GSCALAR(fs_gcs_enabled, "FS_GCS_ENABLE", 0),
|
||||
|
||||
// @Param: FS_CRASH_CHECK
|
||||
// @DisplayName: Crash check action
|
||||
@ -323,94 +323,94 @@ const AP_Param::Info Rover::var_info[] = {
|
||||
// @User: Standard
|
||||
GSCALAR(fs_crash_check, "FS_CRASH_CHECK", FS_CRASH_HOLD),
|
||||
|
||||
// @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
|
||||
// @Units: centimeters
|
||||
// @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
|
||||
// @Units: centimeters
|
||||
// @Range: 0 1000
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
GSCALAR(sonar_trigger_cm, "RNGFND_TRIGGR_CM", 100),
|
||||
// @User: Standard
|
||||
GSCALAR(sonar_trigger_cm, "RNGFND_TRIGGR_CM", 100),
|
||||
|
||||
// @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.
|
||||
// @Units: centimeters
|
||||
// @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.
|
||||
// @Units: centimeters
|
||||
// @Range: -45 45
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
GSCALAR(sonar_turn_angle, "RNGFND_TURN_ANGL", 45),
|
||||
// @User: Standard
|
||||
GSCALAR(sonar_turn_angle, "RNGFND_TURN_ANGL", 45),
|
||||
|
||||
// @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.
|
||||
// @Units: seconds
|
||||
// @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.
|
||||
// @Units: seconds
|
||||
// @Range: 0 100
|
||||
// @Increment: 0.1
|
||||
// @User: Standard
|
||||
GSCALAR(sonar_turn_time, "RNGFND_TURN_TIME", 1.0f),
|
||||
// @User: Standard
|
||||
GSCALAR(sonar_turn_time, "RNGFND_TURN_TIME", 1.0f),
|
||||
|
||||
// @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.
|
||||
// @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.
|
||||
// @Range: 1 100
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
GSCALAR(sonar_debounce, "RNGFND_DEBOUNCE", 2),
|
||||
// @User: Standard
|
||||
GSCALAR(sonar_debounce, "RNGFND_DEBOUNCE", 2),
|
||||
|
||||
// @Param: LEARN_CH
|
||||
// @DisplayName: Learning channel
|
||||
// @Description: RC Channel to use for learning waypoints
|
||||
// @User: Advanced
|
||||
GSCALAR(learn_channel, "LEARN_CH", 7),
|
||||
GSCALAR(learn_channel, "LEARN_CH", 7),
|
||||
|
||||
// @Param: MODE_CH
|
||||
// @DisplayName: Mode channel
|
||||
// @Description: RC Channel to use for driving mode control
|
||||
// @User: Advanced
|
||||
GSCALAR(mode_channel, "MODE_CH", MODE_CHANNEL),
|
||||
GSCALAR(mode_channel, "MODE_CH", MODE_CHANNEL),
|
||||
|
||||
// @Param: MODE1
|
||||
// @DisplayName: Mode1
|
||||
// @Values: 0:Manual,2:LEARNING,3:STEERING,4:HOLD,10:Auto,11:RTL,15:Guided
|
||||
// @User: Standard
|
||||
// @Description: Driving mode for switch position 1 (910 to 1230 and above 2049)
|
||||
GSCALAR(mode1, "MODE1", MODE_1),
|
||||
GSCALAR(mode1, "MODE1", MODE_1),
|
||||
|
||||
// @Param: MODE2
|
||||
// @DisplayName: Mode2
|
||||
// @Description: Driving mode for switch position 2 (1231 to 1360)
|
||||
// @Values: 0:Manual,2:LEARNING,3:STEERING,4:HOLD,10:Auto,11:RTL,15:Guided
|
||||
// @User: Standard
|
||||
GSCALAR(mode2, "MODE2", MODE_2),
|
||||
GSCALAR(mode2, "MODE2", MODE_2),
|
||||
|
||||
// @Param: MODE3
|
||||
// @DisplayName: Mode3
|
||||
// @Description: Driving mode for switch position 3 (1361 to 1490)
|
||||
// @Values: 0:Manual,2:LEARNING,3:STEERING,4:HOLD,10:Auto,11:RTL,15:Guided
|
||||
// @User: Standard
|
||||
GSCALAR(mode3, "MODE3", MODE_3),
|
||||
GSCALAR(mode3, "MODE3", MODE_3),
|
||||
|
||||
// @Param: MODE4
|
||||
// @DisplayName: Mode4
|
||||
// @Description: Driving mode for switch position 4 (1491 to 1620)
|
||||
// @Values: 0:Manual,2:LEARNING,3:STEERING,4:HOLD,10:Auto,11:RTL,15:Guided
|
||||
// @User: Standard
|
||||
GSCALAR(mode4, "MODE4", MODE_4),
|
||||
GSCALAR(mode4, "MODE4", MODE_4),
|
||||
|
||||
// @Param: MODE5
|
||||
// @DisplayName: Mode5
|
||||
// @Description: Driving mode for switch position 5 (1621 to 1749)
|
||||
// @Values: 0:Manual,2:LEARNING,3:STEERING,4:HOLD,10:Auto,11:RTL,15:Guided
|
||||
// @User: Standard
|
||||
GSCALAR(mode5, "MODE5", MODE_5),
|
||||
GSCALAR(mode5, "MODE5", MODE_5),
|
||||
|
||||
// @Param: MODE6
|
||||
// @DisplayName: Mode6
|
||||
// @Description: Driving mode for switch position 6 (1750 to 2049)
|
||||
// @Values: 0:Manual,2:LEARNING,3:STEERING,4:HOLD,10:Auto,11:RTL,15:Guided
|
||||
// @User: Standard
|
||||
GSCALAR(mode6, "MODE6", MODE_6),
|
||||
GSCALAR(mode6, "MODE6", MODE_6),
|
||||
|
||||
// @Param: WP_RADIUS
|
||||
// @DisplayName: Waypoint radius
|
||||
@ -419,7 +419,7 @@ const AP_Param::Info Rover::var_info[] = {
|
||||
// @Range: 0 1000
|
||||
// @Increment: 0.1
|
||||
// @User: Standard
|
||||
GSCALAR(waypoint_radius, "WP_RADIUS", 2.0f),
|
||||
GSCALAR(waypoint_radius, "WP_RADIUS", 2.0f),
|
||||
|
||||
// @Param: TURN_MAX_G
|
||||
// @DisplayName: Turning maximum G force
|
||||
@ -428,19 +428,19 @@ const AP_Param::Info Rover::var_info[] = {
|
||||
// @Range: 0.2 10
|
||||
// @Increment: 0.1
|
||||
// @User: Standard
|
||||
GSCALAR(turn_max_g, "TURN_MAX_G", 2.0f),
|
||||
GSCALAR(turn_max_g, "TURN_MAX_G", 2.0f),
|
||||
|
||||
// @Group: STEER2SRV_
|
||||
// @Path: ../libraries/APM_Control/AP_SteerController.cpp
|
||||
GOBJECT(steerController, "STEER2SRV_", AP_SteerController),
|
||||
GOBJECT(steerController, "STEER2SRV_", AP_SteerController),
|
||||
|
||||
GGROUP(pidSpeedThrottle, "SPEED2THR_", PID),
|
||||
GGROUP(pidSpeedThrottle, "SPEED2THR_", PID),
|
||||
|
||||
// variables not in the g class which contain EEPROM saved variables
|
||||
// variables not in the g class which contain EEPROM saved variables
|
||||
|
||||
// @Group: COMPASS_
|
||||
// @Path: ../libraries/AP_Compass/AP_Compass.cpp
|
||||
GOBJECT(compass, "COMPASS_", Compass),
|
||||
GOBJECT(compass, "COMPASS_", Compass),
|
||||
|
||||
// @Group: SCHED_
|
||||
// @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp
|
||||
@ -565,14 +565,13 @@ const AP_Param::Info Rover::var_info[] = {
|
||||
// @Path: Parameters.cpp
|
||||
GOBJECT(g2, "", ParametersG2),
|
||||
|
||||
AP_VAREND
|
||||
AP_VAREND
|
||||
};
|
||||
|
||||
/*
|
||||
2nd group of parameters
|
||||
*/
|
||||
const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
||||
|
||||
// @Group: STAT
|
||||
// @Path: ../libraries/AP_Stats/AP_Stats.cpp
|
||||
AP_SUBGROUPINFO(stats, "STAT", 1, ParametersG2, AP_Stats),
|
||||
@ -621,16 +620,15 @@ void Rover::load_parameters(void)
|
||||
AP_HAL::panic("Bad var table");
|
||||
}
|
||||
|
||||
if (!g.format_version.load() ||
|
||||
g.format_version != Parameters::k_format_version) {
|
||||
if (!g.format_version.load() ||
|
||||
g.format_version != Parameters::k_format_version) {
|
||||
// erase all parameters
|
||||
cliSerial->println("Firmware change: erasing EEPROM...");
|
||||
AP_Param::erase_all();
|
||||
|
||||
// erase all parameters
|
||||
cliSerial->println("Firmware change: erasing EEPROM...");
|
||||
AP_Param::erase_all();
|
||||
|
||||
// save the current format version
|
||||
g.format_version.set_and_save(Parameters::k_format_version);
|
||||
cliSerial->println("done.");
|
||||
// save the current format version
|
||||
g.format_version.set_and_save(Parameters::k_format_version);
|
||||
cliSerial->println("done.");
|
||||
}
|
||||
|
||||
unsigned long before = micros();
|
||||
|
Loading…
Reference in New Issue
Block a user