Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Rover/Parameters.cpp
9325 views
1
#include "Rover.h"
2
3
#include <AP_Gripper/AP_Gripper.h>
4
5
/*
6
Rover parameter definitions
7
*/
8
9
const AP_Param::Info Rover::var_info[] = {
10
// @Param: FORMAT_VERSION
11
// @DisplayName: Eeprom format version number
12
// @Description: This value is incremented when changes are made to the eeprom format
13
// @User: Advanced
14
GSCALAR(format_version, "FORMAT_VERSION", 1),
15
16
// @Param: LOG_BITMASK
17
// @DisplayName: Log bitmask
18
// @Description: Bitmap of what log types to enable in on-board logger. This value is made up of the sum of each of the log types you want to be saved. On boards supporting microSD cards or other large block-storage devices it is usually best just to enable all basic log types by setting this to 65535.
19
// @Bitmask: 0:Fast Attitude,1:Medium Attitude,2:GPS,3:System Performance,4:Throttle,5:Navigation Tuning,7:IMU,8:Mission Commands,9:Battery Monitor,10:Rangefinder,11:Compass,12:Camera,13:Steering,14:RC Input-Output,19:Raw IMU,20:Video Stabilization,21:Optical Flow
20
// @User: Advanced
21
GSCALAR(log_bitmask, "LOG_BITMASK", DEFAULT_LOG_BITMASK),
22
23
// @Param: RST_SWITCH_CH
24
// @DisplayName: Reset Switch Channel
25
// @Description: RC channel to use to reset to last flight mode after geofence takeover.
26
// @User: Advanced
27
GSCALAR(reset_switch_chan, "RST_SWITCH_CH", 0),
28
29
// @Param: INITIAL_MODE
30
// @DisplayName: Initial driving mode
31
// @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.
32
// @CopyValuesFrom: MODE1
33
// @User: Advanced
34
GSCALAR(initial_mode, "INITIAL_MODE", (int8_t)Mode::Number::MANUAL),
35
36
// SYSID_THISMAV was here
37
38
// SYSID_MYGCS was here
39
40
// TELEM_DELAY was here
41
42
// @Param: GCS_PID_MASK
43
// @DisplayName: GCS PID tuning mask
44
// @Description: bitmask of PIDs to send MAVLink PID_TUNING messages for
45
// @User: Advanced
46
// @Bitmask: 0:Steering,1:Throttle,2:Pitch,3:Left Wheel,4:Right Wheel,5:Sailboat Heel,6:Velocity North,7:Velocity East
47
GSCALAR(gcs_pid_mask, "GCS_PID_MASK", 0),
48
49
// @Param: AUTO_TRIGGER_PIN
50
// @DisplayName: Auto mode trigger pin
51
// @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.
52
// @Values: -1:Disabled,0:APM TriggerPin0,1:APM TriggerPin1,2:APM TriggerPin2,3:APM TriggerPin3,4:APM TriggerPin4,5:APM TriggerPin5,6:APM TriggerPin6,7:APM TriggerPin7,8:APM TriggerPin8,50:AUX1,51:AUX2,52:AUX3,53:AUX4,54:AUX5,55:AUX6
53
// @Range: -1 127
54
// @User: Standard
55
GSCALAR(auto_trigger_pin, "AUTO_TRIGGER_PIN", -1),
56
57
// @Param: AUTO_KICKSTART
58
// @DisplayName: Auto mode trigger kickstart acceleration
59
// @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
60
// @Units: m/s/s
61
// @Range: 0 20
62
// @Increment: 0.1
63
// @User: Standard
64
GSCALAR(auto_kickstart, "AUTO_KICKSTART", 0.0f),
65
66
// @Param: CRUISE_SPEED
67
// @DisplayName: Target cruise speed in auto modes
68
// @Description: The target speed in auto missions.
69
// @Units: m/s
70
// @Range: 0 100
71
// @Increment: 0.1
72
// @User: Standard
73
GSCALAR(speed_cruise, "CRUISE_SPEED", CRUISE_SPEED),
74
75
76
// @Param: CRUISE_THROTTLE
77
// @DisplayName: Base throttle percentage in auto
78
// @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.
79
// @Units: %
80
// @Range: 0 100
81
// @Increment: 1
82
// @User: Standard
83
GSCALAR(throttle_cruise, "CRUISE_THROTTLE", 50),
84
85
// @Param: PILOT_STEER_TYPE
86
// @DisplayName: Pilot input steering type
87
// @Description: Pilot RC input interpretation
88
// @Values: 0:Default,1:Two Paddles Input,2:Direction reversed when backing up,3:Direction unchanged when backing up
89
// @User: Standard
90
GSCALAR(pilot_steer_type, "PILOT_STEER_TYPE", 0),
91
92
// @Param: FS_ACTION
93
// @DisplayName: Failsafe Action
94
// @Description: What to do on a failsafe event
95
// @Values: 0:Nothing,1:RTL,2:Hold,3:SmartRTL or RTL,4:SmartRTL or Hold,5:Terminate,6:Loiter or Hold
96
// @User: Standard
97
GSCALAR(fs_action, "FS_ACTION", (int8_t)FailsafeAction::Hold),
98
99
// @Param: FS_TIMEOUT
100
// @DisplayName: Failsafe timeout
101
// @Description: The time in seconds that a failsafe condition must persist before the failsafe action is triggered
102
// @Units: s
103
// @Range: 1 100
104
// @Increment: 0.5
105
// @User: Standard
106
GSCALAR(fs_timeout, "FS_TIMEOUT", 1.5),
107
108
// @Param: FS_THR_ENABLE
109
// @DisplayName: Throttle Failsafe Enable
110
// @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.
111
// @Values: 0:Disabled,1:Enabled,2:Enabled Continue with Mission in Auto
112
// @User: Standard
113
GSCALAR(fs_throttle_enabled, "FS_THR_ENABLE", FS_THR_ENABLED),
114
115
// @Param: FS_THR_VALUE
116
// @DisplayName: Throttle Failsafe Value
117
// @Description: The PWM level on the throttle channel below which throttle failsafe triggers.
118
// @Range: 910 1100
119
// @Increment: 1
120
// @User: Standard
121
GSCALAR(fs_throttle_value, "FS_THR_VALUE", 910),
122
123
// @Param: FS_GCS_ENABLE
124
// @DisplayName: GCS failsafe enable
125
// @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.
126
// @Values: 0:Disabled,1:Enabled,2:Enabled Continue with Mission in Auto
127
// @User: Standard
128
GSCALAR(fs_gcs_enabled, "FS_GCS_ENABLE", FS_GCS_DISABLED),
129
130
// @Param: FS_CRASH_CHECK
131
// @DisplayName: Crash check action
132
// @Description: What to do on a crash event. When enabled the rover will go to hold if a crash is detected.
133
// @Values: 0:Disabled,1:Hold,2:HoldAndDisarm
134
// @User: Standard
135
GSCALAR(fs_crash_check, "FS_CRASH_CHECK", FS_CRASH_DISABLE),
136
137
// @Param: FS_EKF_ACTION
138
// @DisplayName: EKF Failsafe Action
139
// @Description: Controls the action that will be taken when an EKF failsafe is invoked
140
// @Values: 0:Disabled,1:Hold,2:ReportOnly
141
// @User: Advanced
142
GSCALAR(fs_ekf_action, "FS_EKF_ACTION", FS_EKF_HOLD),
143
144
// @Param: FS_EKF_THRESH
145
// @DisplayName: EKF failsafe variance threshold
146
// @Description: Allows setting the maximum acceptable compass and velocity variance
147
// @Values: 0.6:Strict, 0.8:Default, 1.0:Relaxed
148
// @User: Advanced
149
GSCALAR(fs_ekf_thresh, "FS_EKF_THRESH", 0.8f),
150
151
// @Param: MODE_CH
152
// @DisplayName: Mode channel
153
// @Description: RC Channel to use for driving mode control
154
// @User: Advanced
155
GSCALAR(mode_channel, "MODE_CH", MODE_CHANNEL),
156
157
// @Param: MODE1
158
// @DisplayName: Mode1
159
// @Values: 0:Manual,1:Acro,3:Steering,4:Hold,5:Loiter,6:Follow,7:Simple,8:Dock,9:Circle,10:Auto,11:RTL,12:SmartRTL,15:Guided
160
// @User: Standard
161
// @Description: Driving mode for switch position 1 (910 to 1230 and above 2049)
162
GSCALAR(mode1, "MODE1", (int8_t)Mode::Number::MANUAL),
163
164
// @Param: MODE2
165
// @DisplayName: Mode2
166
// @Description: Driving mode for switch position 2 (1231 to 1360)
167
// @CopyValuesFrom: MODE1
168
// @User: Standard
169
GSCALAR(mode2, "MODE2", (int8_t)Mode::Number::MANUAL),
170
171
// @Param: MODE3
172
// @CopyFieldsFrom: MODE1
173
// @DisplayName: Mode3
174
// @Description: Driving mode for switch position 3 (1361 to 1490)
175
GSCALAR(mode3, "MODE3", (int8_t)Mode::Number::MANUAL),
176
177
// @Param: MODE4
178
// @CopyFieldsFrom: MODE1
179
// @DisplayName: Mode4
180
// @Description: Driving mode for switch position 4 (1491 to 1620)
181
GSCALAR(mode4, "MODE4", (int8_t)Mode::Number::MANUAL),
182
183
// @Param: MODE5
184
// @CopyFieldsFrom: MODE1
185
// @DisplayName: Mode5
186
// @Description: Driving mode for switch position 5 (1621 to 1749)
187
GSCALAR(mode5, "MODE5", (int8_t)Mode::Number::MANUAL),
188
189
// @Param: MODE6
190
// @CopyFieldsFrom: MODE1
191
// @DisplayName: Mode6
192
// @Description: Driving mode for switch position 6 (1750 to 2049)
193
GSCALAR(mode6, "MODE6", (int8_t)Mode::Number::MANUAL),
194
195
// variables not in the g class which contain EEPROM saved variables
196
197
// @Group: COMPASS_
198
// @Path: ../libraries/AP_Compass/AP_Compass.cpp
199
GOBJECT(compass, "COMPASS_", Compass),
200
201
// @Group: SCHED_
202
// @Path: ../libraries/AP_Scheduler/AP_Scheduler.cpp
203
GOBJECT(scheduler, "SCHED_", AP_Scheduler),
204
205
// @Group: BARO
206
// @Path: ../libraries/AP_Baro/AP_Baro.cpp
207
GOBJECT(barometer, "BARO", AP_Baro),
208
209
#if AP_RELAY_ENABLED
210
// @Group: RELAY
211
// @Path: ../libraries/AP_Relay/AP_Relay.cpp
212
GOBJECT(relay, "RELAY", AP_Relay),
213
#endif
214
215
// @Group: RCMAP_
216
// @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp
217
GOBJECT(rcmap, "RCMAP_", RCMapper),
218
219
// SR0 through SR6 were here
220
221
// AP_SerialManager was here
222
223
#if AP_RANGEFINDER_ENABLED
224
// @Group: RNGFND
225
// @Path: ../libraries/AP_RangeFinder/AP_RangeFinder.cpp
226
GOBJECT(rangefinder, "RNGFND", RangeFinder),
227
#endif
228
229
// @Group: INS
230
// @Path: ../libraries/AP_InertialSensor/AP_InertialSensor.cpp
231
GOBJECT(ins, "INS", AP_InertialSensor),
232
233
#if AP_SIM_ENABLED
234
// @Group: SIM_
235
// @Path: ../libraries/SITL/SITL.cpp
236
GOBJECT(sitl, "SIM_", SITL::SIM),
237
#endif
238
239
// @Group: AHRS_
240
// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
241
GOBJECT(ahrs, "AHRS_", AP_AHRS),
242
243
#if AP_CAMERA_ENABLED
244
// @Group: CAM
245
// @Path: ../libraries/AP_Camera/AP_Camera.cpp
246
GOBJECT(camera, "CAM", AP_Camera),
247
#endif
248
249
#if AC_PRECLAND_ENABLED
250
// @Group: PLND_
251
// @Path: ../libraries/AC_PrecLand/AC_PrecLand.cpp
252
GOBJECT(precland, "PLND_", AC_PrecLand),
253
#endif
254
255
#if HAL_MOUNT_ENABLED
256
// @Group: MNT
257
// @Path: ../libraries/AP_Mount/AP_Mount.cpp
258
GOBJECT(camera_mount, "MNT", AP_Mount),
259
#endif
260
261
// @Group: ARMING_
262
// @Path: ../libraries/AP_Arming/AP_Arming.cpp
263
GOBJECT(arming, "ARMING_", AP_Arming),
264
265
// @Group: BATT
266
// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp
267
GOBJECT(battery, "BATT", AP_BattMonitor),
268
269
// @Group: BRD_
270
// @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp
271
GOBJECT(BoardConfig, "BRD_", AP_BoardConfig),
272
273
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
274
// @Group: CAN_
275
// @Path: ../libraries/AP_CANManager/AP_CANManager.cpp
276
GOBJECT(can_mgr, "CAN_", AP_CANManager),
277
#endif
278
279
// GPS driver
280
// @Group: GPS
281
// @Path: ../libraries/AP_GPS/AP_GPS.cpp
282
GOBJECT(gps, "GPS", AP_GPS),
283
284
#if HAL_NAVEKF2_AVAILABLE
285
// @Group: EK2_
286
// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp
287
GOBJECTN(ahrs.EKF2, NavEKF2, "EK2_", NavEKF2),
288
#endif
289
290
#if HAL_NAVEKF3_AVAILABLE
291
// @Group: EK3_
292
// @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp
293
GOBJECTN(ahrs.EKF3, NavEKF3, "EK3_", NavEKF3),
294
#endif
295
296
// @Group: MIS_
297
// @Path: ../libraries/AP_Mission/AP_Mission.cpp
298
GOBJECTN(mode_auto.mission, mission, "MIS_", AP_Mission),
299
300
#if AP_RSSI_ENABLED
301
// @Group: RSSI_
302
// @Path: ../libraries/AP_RSSI/AP_RSSI.cpp
303
GOBJECT(rssi, "RSSI_", AP_RSSI),
304
#endif
305
306
// @Group: NTF_
307
// @Path: ../libraries/AP_Notify/AP_Notify.cpp
308
GOBJECT(notify, "NTF_", AP_Notify),
309
310
#if HAL_BUTTON_ENABLED
311
// @Group: BTN_
312
// @Path: ../libraries/AP_Button/AP_Button.cpp
313
GOBJECT(button, "BTN_", AP_Button),
314
#endif
315
316
// @Group:
317
// @Path: Parameters.cpp
318
GOBJECT(g2, "", ParametersG2),
319
320
#if OSD_ENABLED || OSD_PARAM_ENABLED
321
// @Group: OSD
322
// @Path: ../libraries/AP_OSD/AP_OSD.cpp
323
GOBJECT(osd, "OSD", AP_OSD),
324
#endif
325
326
#if AP_OPTICALFLOW_ENABLED
327
// @Group: FLOW
328
// @Path: ../libraries/AP_OpticalFlow/AP_OpticalFlow.cpp
329
GOBJECT(optflow, "FLOW", AP_OpticalFlow),
330
#endif
331
332
// @Group:
333
// @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp
334
PARAM_VEHICLE_INFO,
335
336
#if HAL_GCS_ENABLED
337
// @Group: MAV
338
// @Path: ../libraries/GCS_MAVLink/GCS.cpp
339
GOBJECT(_gcs, "MAV", GCS),
340
#endif
341
342
AP_VAREND
343
};
344
345
/*
346
2nd group of parameters
347
*/
348
const AP_Param::GroupInfo ParametersG2::var_info[] = {
349
// 1 was AP_Stats
350
351
// 2 was SYSID_ENFORCE
352
353
// @Group: SERVO
354
// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp
355
AP_SUBGROUPINFO(servo_channels, "SERVO", 3, ParametersG2, SRV_Channels),
356
357
// @Group: RC
358
// @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h
359
AP_SUBGROUPINFO(rc_channels, "RC", 4, ParametersG2, RC_Channels_Rover),
360
361
#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED
362
// @Group: AFS_
363
// @Path: ../libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp
364
AP_SUBGROUPINFO(afs, "AFS_", 5, ParametersG2, AP_AdvancedFailsafe),
365
#endif
366
367
#if AP_BEACON_ENABLED
368
// @Group: BCN
369
// @Path: ../libraries/AP_Beacon/AP_Beacon.cpp
370
AP_SUBGROUPINFO(beacon, "BCN", 6, ParametersG2, AP_Beacon),
371
#endif
372
373
// 7 was used by AP_VisualOdometry
374
375
// @Group: MOT_
376
// @Path: ../libraries/AR_Motors/AP_MotorsUGV.cpp
377
AP_SUBGROUPINFO(motors, "MOT_", 8, ParametersG2, AP_MotorsUGV),
378
379
// @Group: WENC
380
// @Path: ../libraries/AP_WheelEncoder/AP_WheelEncoder.cpp
381
AP_SUBGROUPINFO(wheel_encoder, "WENC", 9, ParametersG2, AP_WheelEncoder),
382
383
// @Group: ATC
384
// @Path: ../libraries/APM_Control/AR_AttitudeControl.cpp
385
AP_SUBGROUPINFO(attitude_control, "ATC", 10, ParametersG2, AR_AttitudeControl),
386
387
// @Param: TURN_RADIUS
388
// @DisplayName: Turn radius of vehicle
389
// @Description: Turn radius of vehicle in meters while at low speeds. Lower values produce tighter turns in steering mode
390
// @Units: m
391
// @Range: 0 10
392
// @Increment: 0.1
393
// @User: Standard
394
AP_GROUPINFO("TURN_RADIUS", 11, ParametersG2, turn_radius, 0.9),
395
396
// @Param: ACRO_TURN_RATE
397
// @DisplayName: Acro mode turn rate maximum
398
// @Description: Acro mode turn rate maximum
399
// @Units: deg/s
400
// @Range: 0 360
401
// @Increment: 1
402
// @User: Standard
403
AP_GROUPINFO("ACRO_TURN_RATE", 12, ParametersG2, acro_turn_rate, 180.0f),
404
405
// @Group: SRTL_
406
// @Path: ../libraries/AP_SmartRTL/AP_SmartRTL.cpp
407
AP_SUBGROUPINFO(smart_rtl, "SRTL_", 13, ParametersG2, AP_SmartRTL),
408
409
// 14 was WP_SPEED and should not be re-used
410
411
// @Param: RTL_SPEED
412
// @DisplayName: Return-to-Launch speed default
413
// @Description: Return-to-Launch speed default. If zero use WP_SPEED or CRUISE_SPEED.
414
// @Units: m/s
415
// @Range: 0 100
416
// @Increment: 0.1
417
// @User: Standard
418
AP_GROUPINFO("RTL_SPEED", 15, ParametersG2, rtl_speed, 0.0f),
419
420
// @Param: FRAME_CLASS
421
// @DisplayName: Frame Class
422
// @Description: Frame Class
423
// @Values: 0:Undefined,1:Rover,2:Boat,3:BalanceBot
424
// @User: Standard
425
AP_GROUPINFO("FRAME_CLASS", 16, ParametersG2, frame_class, 1),
426
427
#if HAL_PROXIMITY_ENABLED
428
// @Group: PRX
429
// @Path: ../libraries/AP_Proximity/AP_Proximity.cpp
430
AP_SUBGROUPINFO(proximity, "PRX", 18, ParametersG2, AP_Proximity),
431
#endif
432
433
#if AP_AVOIDANCE_ENABLED
434
// @Group: AVOID_
435
// @Path: ../libraries/AC_Avoidance/AC_Avoid.cpp
436
AP_SUBGROUPINFO(avoid, "AVOID_", 19, ParametersG2, AC_Avoid),
437
#endif
438
439
// 20 was PIVOT_TURN_RATE and should not be re-used
440
441
// @Param: BAL_PITCH_MAX
442
// @DisplayName: BalanceBot Maximum Pitch
443
// @Description: Pitch angle in degrees at 100% throttle
444
// @Units: deg
445
// @Range: 0 15
446
// @Increment: 0.1
447
// @User: Standard
448
AP_GROUPINFO("BAL_PITCH_MAX", 21, ParametersG2, bal_pitch_max, 10),
449
450
// @Param: CRASH_ANGLE
451
// @DisplayName: Crash Angle
452
// @Description: Pitch/Roll angle limit in degrees for crash check. Zero disables check
453
// @Units: deg
454
// @Range: 0 60
455
// @Increment: 1
456
// @User: Standard
457
AP_GROUPINFO("CRASH_ANGLE", 22, ParametersG2, crash_angle, 0),
458
459
#if AP_FOLLOW_ENABLED
460
// @Group: FOLL
461
// @Path: ../libraries/AP_Follow/AP_Follow.cpp
462
AP_SUBGROUPINFO(follow, "FOLL", 23, ParametersG2, AP_Follow),
463
#endif
464
465
// @Param: FRAME_TYPE
466
// @DisplayName: Frame Type
467
// @Description: Frame Type
468
// @Values: 0:Default,1:Omni3,2:OmniX,3:OmniPlus,4:Omni3Mecanum
469
// @User: Standard
470
// @RebootRequired: True
471
AP_GROUPINFO("FRAME_TYPE", 24, ParametersG2, frame_type, 0),
472
473
// @Param: LOIT_TYPE
474
// @DisplayName: Loiter type
475
// @Description: Loiter behaviour when moving to the target point
476
// @Values: 0:Forward or reverse to target point,1:Always face bow towards target point,2:Always face stern towards target point
477
// @User: Standard
478
AP_GROUPINFO("LOIT_TYPE", 25, ParametersG2, loit_type, 0),
479
480
#if HAL_SPRAYER_ENABLED
481
// @Group: SPRAY_
482
// @Path: ../libraries/AC_Sprayer/AC_Sprayer.cpp
483
AP_SUBGROUPINFO(sprayer, "SPRAY_", 26, ParametersG2, AC_Sprayer),
484
#endif
485
486
// @Group: WRC
487
// @Path: ../libraries/AP_WheelEncoder/AP_WheelRateControl.cpp
488
AP_SUBGROUPINFO(wheel_rate_control, "WRC", 27, ParametersG2, AP_WheelRateControl),
489
490
#if HAL_RALLY_ENABLED
491
// @Group: RALLY_
492
// @Path: AP_Rally.cpp,../libraries/AP_Rally/AP_Rally.cpp
493
AP_SUBGROUPINFO(rally, "RALLY_", 28, ParametersG2, AP_Rally_Rover),
494
#endif
495
496
// @Param: SIMPLE_TYPE
497
// @DisplayName: Simple_Type
498
// @Description: Simple mode types
499
// @Values: 0:InitialHeading,1:CardinalDirections
500
// @User: Standard
501
// @RebootRequired: True
502
AP_GROUPINFO("SIMPLE_TYPE", 29, ParametersG2, simple_type, 0),
503
504
// @Param: LOIT_RADIUS
505
// @DisplayName: Loiter radius
506
// @Description: Vehicle will drift when within this distance of the target position
507
// @Units: m
508
// @Range: 0 20
509
// @Increment: 1
510
// @User: Standard
511
AP_GROUPINFO("LOIT_RADIUS", 30, ParametersG2, loit_radius, 2),
512
513
// @Group: WNDVN_
514
// @Path: ../libraries/AP_WindVane/AP_WindVane.cpp
515
AP_SUBGROUPINFO(windvane, "WNDVN_", 31, ParametersG2, AP_WindVane),
516
517
// 32 to 36 were old sailboat params
518
519
// 37 was airspeed
520
521
// @Param: MIS_DONE_BEHAVE
522
// @DisplayName: Mission done behave
523
// @Description: Behaviour after mission completes
524
// @Values: 0:Hold in Auto Mode,1:Loiter in Auto Mode,2:Acro Mode,3:Manual Mode
525
// @User: Standard
526
AP_GROUPINFO("MIS_DONE_BEHAVE", 38, ParametersG2, mis_done_behave, 0),
527
528
// 39 was AP_Gripper
529
530
// @Param: BAL_PITCH_TRIM
531
// @DisplayName: Balance Bot pitch trim angle
532
// @Description: Balance Bot pitch trim for balancing. This offsets the tilt of the center of mass.
533
// @Units: deg
534
// @Range: -2 2
535
// @Increment: 0.1
536
// @User: Standard
537
AP_GROUPINFO("BAL_PITCH_TRIM", 40, ParametersG2, bal_pitch_trim, 0),
538
539
// 41 was Scripting
540
541
// @Param: STICK_MIXING
542
// @DisplayName: Stick Mixing
543
// @Description: When enabled, this adds steering user stick input in auto modes, allowing the user to have some degree of control without changing modes.
544
// @Values: 0:Disabled,1:Enabled
545
// @User: Advanced
546
AP_GROUPINFO("STICK_MIXING", 42, ParametersG2, stick_mixing, 0),
547
548
// @Group: WP_
549
// @Path: ../libraries/AR_WPNav/AR_WPNav.cpp
550
AP_SUBGROUPINFO(wp_nav, "WP_", 43, ParametersG2, AR_WPNav_OA),
551
552
// @Group: SAIL_
553
// @Path: sailboat.cpp
554
AP_SUBGROUPINFO(sailboat, "SAIL_", 44, ParametersG2, Sailboat),
555
556
#if AP_OAPATHPLANNER_ENABLED
557
// @Group: OA_
558
// @Path: ../libraries/AC_Avoidance/AP_OAPathPlanner.cpp
559
AP_SUBGROUPINFO(oa, "OA_", 45, ParametersG2, AP_OAPathPlanner),
560
#endif
561
562
// @Param: SPEED_MAX
563
// @DisplayName: Speed maximum
564
// @Description: Maximum speed vehicle can obtain at full throttle. If 0, it will be estimated based on CRUISE_SPEED and CRUISE_THROTTLE.
565
// @Units: m/s
566
// @Range: 0 30
567
// @Increment: 0.1
568
// @User: Advanced
569
AP_GROUPINFO("SPEED_MAX", 46, ParametersG2, speed_max, 0.0f),
570
571
// @Param: LOIT_SPEED_GAIN
572
// @DisplayName: Loiter speed gain
573
// @Description: Determines how aggressively LOITER tries to correct for drift from loiter point. Higher is faster but default should be acceptable.
574
// @Range: 0 5
575
// @Increment: 0.01
576
// @User: Advanced
577
AP_GROUPINFO("LOIT_SPEED_GAIN", 47, ParametersG2, loiter_speed_gain, 0.5f),
578
579
// @Param: FS_OPTIONS
580
// @DisplayName: Failsafe Options
581
// @Description: Bitmask to enable failsafe options
582
// @Bitmask: 0:Failsafe enabled in Hold mode
583
// @User: Advanced
584
AP_GROUPINFO("FS_OPTIONS", 48, ParametersG2, fs_options, 0),
585
586
#if HAL_TORQEEDO_ENABLED
587
// @Group: TRQ
588
// @Path: ../libraries/AP_Torqeedo/AP_Torqeedo.cpp
589
AP_SUBGROUPINFO(torqeedo, "TRQ", 49, ParametersG2, AP_Torqeedo),
590
#endif
591
592
// @Group: PSC
593
// @Path: ../libraries/APM_Control/AR_PosControl.cpp
594
AP_SUBGROUPINFO(pos_control, "PSC", 51, ParametersG2, AR_PosControl),
595
596
// @Param: GUID_OPTIONS
597
// @DisplayName: Guided mode options
598
// @Description: Options that can be applied to change guided mode behaviour
599
// @Bitmask: 6:SCurves used for navigation
600
// @User: Advanced
601
AP_GROUPINFO("GUID_OPTIONS", 52, ParametersG2, guided_options, 0),
602
603
// @Param: MANUAL_OPTIONS
604
// @DisplayName: Manual mode options
605
// @Description: Manual mode specific options
606
// @Bitmask: 0:Enable steering speed scaling
607
// @User: Advanced
608
AP_GROUPINFO("MANUAL_OPTIONS", 53, ParametersG2, manual_options, 0),
609
610
#if MODE_DOCK_ENABLED
611
// @Group: DOCK
612
// @Path: mode_dock.cpp
613
AP_SUBGROUPPTR(mode_dock_ptr, "DOCK", 54, ParametersG2, ModeDock),
614
#endif
615
616
// @Param: MANUAL_STR_EXPO
617
// @DisplayName: Manual Steering Expo
618
// @Description: Manual steering expo to allow faster steering when stick at edges
619
// @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High
620
// @Range: -0.5 0.95
621
// @User: Advanced
622
AP_GROUPINFO("MANUAL_STR_EXPO", 55, ParametersG2, manual_steering_expo, 0),
623
624
// @Param: FS_GCS_TIMEOUT
625
// @DisplayName: GCS failsafe timeout
626
// @Description: Timeout before triggering the GCS failsafe
627
// @Units: s
628
// @Range: 2 120
629
// @Increment: 1
630
// @User: Standard
631
AP_GROUPINFO("FS_GCS_TIMEOUT", 56, ParametersG2, fs_gcs_timeout, 5),
632
633
// @Group: CIRC
634
// @Path: mode_circle.cpp
635
AP_SUBGROUPINFO(mode_circle, "CIRC", 57, ParametersG2, ModeCircle),
636
637
AP_GROUPEND
638
};
639
640
// These auxiliary channel param descriptions are here so that users of beta Mission Planner (which uses the master branch as its source of descriptions)
641
// can get them. These lines can be removed once Rover-3.6-beta testing begins or we improve the source of descriptions for GCSs.
642
//
643
// @Param: CH7_OPTION
644
// @DisplayName: Channel 7 option
645
// @Description: What to do use channel 7 for
646
// @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
647
// @User: Standard
648
649
// @Param: AUX_CH
650
// @DisplayName: Auxiliary switch channel
651
// @Description: RC Channel to use for auxiliary functions including saving waypoints
652
// @User: Advanced
653
654
// @Param: PIVOT_TURN_ANGLE
655
// @DisplayName: Pivot turn angle
656
// @Description: Navigation angle threshold in degrees to switch to pivot steering. This allows you to setup a skid steering rover to turn on the spot in auto mode when the angle it needs to turn it greater than this angle. An angle of zero means to disable pivot turning. Note that you will probably also want to set a low value for WP_RADIUS to get neat turns.
657
// @Units: deg
658
// @Range: 0 360
659
// @Increment: 1
660
// @User: Standard
661
662
// @Param: PIVOT_TURN_RATE
663
// @DisplayName: Pivot turn rate
664
// @Description: Desired pivot turn rate in deg/s.
665
// @Units: deg/s
666
// @Range: 0 360
667
// @Increment: 1
668
// @User: Standard
669
670
ParametersG2::ParametersG2(void)
671
:
672
#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED
673
afs(),
674
#endif
675
#if AP_BEACON_ENABLED
676
beacon(),
677
#endif
678
wheel_rate_control(wheel_encoder),
679
motors(wheel_rate_control),
680
attitude_control(),
681
smart_rtl(),
682
#if HAL_PROXIMITY_ENABLED
683
proximity(),
684
#endif
685
#if MODE_DOCK_ENABLED
686
mode_dock_ptr(&rover.mode_dock),
687
#endif
688
#if AP_AVOIDANCE_ENABLED
689
avoid(),
690
#endif
691
#if AP_FOLLOW_ENABLED
692
follow(),
693
#endif
694
windvane(),
695
wp_nav(attitude_control, pos_control),
696
sailboat(),
697
pos_control(attitude_control)
698
{
699
AP_Param::setup_object_defaults(this, var_info);
700
}
701
702
703
/*
704
This is a conversion table from old parameter values to new
705
parameter names. The startup code looks for saved values of the old
706
parameters and will copy them across to the new parameters if the
707
new parameter does not yet have a saved value. It then saves the new
708
value.
709
710
Note that this works even if the old parameter has been removed. It
711
relies on the old k_param index not being removed
712
713
The second column below is the index in the var_info[] table for the
714
old object. This should be zero for top level parameters.
715
*/
716
const AP_Param::ConversionInfo conversion_table[] = {
717
{ Parameters::k_param_battery_monitoring, 0, AP_PARAM_INT8, "BATT_MONITOR" },
718
{ Parameters::k_param_battery_volt_pin, 0, AP_PARAM_INT8, "BATT_VOLT_PIN" },
719
{ Parameters::k_param_battery_curr_pin, 0, AP_PARAM_INT8, "BATT_CURR_PIN" },
720
{ Parameters::k_param_volt_div_ratio, 0, AP_PARAM_FLOAT, "BATT_VOLT_MULT" },
721
{ Parameters::k_param_curr_amp_per_volt, 0, AP_PARAM_FLOAT, "BATT_AMP_PERVOLT" },
722
{ Parameters::k_param_pack_capacity, 0, AP_PARAM_INT32, "BATT_CAPACITY" },
723
{ Parameters::k_param_serial0_baud, 0, AP_PARAM_INT16, "SERIAL0_BAUD" },
724
{ Parameters::k_param_serial1_baud, 0, AP_PARAM_INT16, "SERIAL1_BAUD" },
725
{ Parameters::k_param_serial2_baud, 0, AP_PARAM_INT16, "SERIAL2_BAUD" },
726
{ Parameters::k_param_throttle_min_old, 0, AP_PARAM_INT8, "MOT_THR_MIN" },
727
{ Parameters::k_param_throttle_max_old, 0, AP_PARAM_INT8, "MOT_THR_MAX" },
728
{ Parameters::k_param_compass_enabled_deprecated, 0, AP_PARAM_INT8, "COMPASS_ENABLE" },
729
{ Parameters::k_param_waypoint_radius_old, 0, AP_PARAM_FLOAT, "WP_RADIUS" },
730
{ Parameters::k_param_g2, 299, AP_PARAM_INT16, "WP_PIVOT_ANGLE" },
731
{ Parameters::k_param_g2, 363, AP_PARAM_INT16, "WP_PIVOT_RATE" },
732
{ Parameters::k_param_g2, 491, AP_PARAM_FLOAT, "WP_PIVOT_DELAY" },
733
{ Parameters::k_param_g2, 32, AP_PARAM_FLOAT, "SAIL_ANGLE_MIN" },
734
{ Parameters::k_param_g2, 33, AP_PARAM_FLOAT, "SAIL_ANGLE_MAX" },
735
{ Parameters::k_param_g2, 34, AP_PARAM_FLOAT, "SAIL_ANGLE_IDEAL" },
736
{ Parameters::k_param_g2, 35, AP_PARAM_FLOAT, "SAIL_HEEL_MAX" },
737
{ Parameters::k_param_g2, 36, AP_PARAM_FLOAT, "SAIL_NO_GO_ANGLE" },
738
{ Parameters::k_param_turn_max_g_old, 0, AP_PARAM_FLOAT, "ATC_TURN_MAX_G" },
739
{ Parameters::k_param_g2, 82, AP_PARAM_INT8 , "PRX1_TYPE" },
740
{ Parameters::k_param_g2, 146, AP_PARAM_INT8 , "PRX1_ORIENT" },
741
{ Parameters::k_param_g2, 210, AP_PARAM_INT16, "PRX1_YAW_CORR" },
742
{ Parameters::k_param_g2, 274, AP_PARAM_INT16, "PRX1_IGN_ANG1" },
743
{ Parameters::k_param_g2, 338, AP_PARAM_INT8, "PRX1_IGN_WID1" },
744
{ Parameters::k_param_g2, 402, AP_PARAM_INT16, "PRX1_IGN_ANG2" },
745
{ Parameters::k_param_g2, 466, AP_PARAM_INT8, "PRX1_IGN_WID2" },
746
{ Parameters::k_param_g2, 530, AP_PARAM_INT16, "PRX1_IGN_ANG3" },
747
{ Parameters::k_param_g2, 594, AP_PARAM_INT8, "PRX1_IGN_WID3" },
748
{ Parameters::k_param_g2, 658, AP_PARAM_INT16, "PRX1_IGN_ANG4" },
749
{ Parameters::k_param_g2, 722, AP_PARAM_INT8, "PRX1_IGN_WID4" },
750
{ Parameters::k_param_g2, 1234, AP_PARAM_FLOAT, "PRX1_MIN" },
751
{ Parameters::k_param_g2, 1298, AP_PARAM_FLOAT, "PRX1_MAX" },
752
{ Parameters::k_param_g2, 113, AP_PARAM_INT8, "TRQ1_TYPE" },
753
{ Parameters::k_param_g2, 177, AP_PARAM_INT8, "TRQ1_ONOFF_PIN" },
754
{ Parameters::k_param_g2, 241, AP_PARAM_INT8, "TRQ1_DE_PIN" },
755
{ Parameters::k_param_g2, 305, AP_PARAM_INT16, "TRQ1_OPTIONS" },
756
{ Parameters::k_param_g2, 369, AP_PARAM_INT8, "TRQ1_POWER" },
757
{ Parameters::k_param_g2, 433, AP_PARAM_FLOAT, "TRQ1_SLEW_TIME" },
758
{ Parameters::k_param_g2, 497, AP_PARAM_FLOAT, "TRQ1_DIR_DELAY" },
759
};
760
761
762
void Rover::load_parameters(void)
763
{
764
AP_Vehicle::load_parameters(g.format_version, Parameters::k_format_version);
765
766
AP_Param::convert_old_parameters(&conversion_table[0], ARRAY_SIZE(conversion_table));
767
768
AP_Param::set_frame_type_flags(AP_PARAM_FRAME_ROVER);
769
770
SRV_Channels::set_default_function(CH_1, SRV_Channel::k_steering);
771
SRV_Channels::set_default_function(CH_3, SRV_Channel::k_throttle);
772
773
if (is_balancebot()) {
774
g2.crash_angle.set_default(30);
775
}
776
777
SRV_Channels::upgrade_parameters();
778
779
// convert CH7_OPTION to RC7_OPTION for Rover-3.4 to 3.5 upgrade
780
const AP_Param::ConversionInfo ch7_option_info = { Parameters::k_param_ch7_option, 0, AP_PARAM_INT8, "RC7_OPTION" };
781
AP_Int8 ch7_opt_old;
782
if (AP_Param::find_old_parameter(&ch7_option_info, &ch7_opt_old)) {
783
const uint8_t ch7_opt_map[] = {0,7,50,41,51,52,53,54,16,4,42,55,56};
784
const uint8_t ch7_opt_old_val = (uint8_t)ch7_opt_old.get();
785
if (ch7_opt_old_val < ARRAY_SIZE(ch7_opt_map)) {
786
AP_Param::set_default_by_name(ch7_option_info.new_name, ch7_opt_map[ch7_opt_old_val]);
787
}
788
}
789
790
// set AR_WPNav's WP_SPEED to be old WP_SPEED (if set) or CRUISE_SPEED (if set)
791
const AP_Param::ConversionInfo wp_speed_old_info = { Parameters::k_param_g2, 14, AP_PARAM_FLOAT, "WP_SPEED" };
792
const AP_Param::ConversionInfo cruise_speed_info = { Parameters::k_param_speed_cruise, 0, AP_PARAM_FLOAT, "WP_SPEED" };
793
AP_Float wp_speed_old;
794
if (AP_Param::find_old_parameter(&wp_speed_old_info, &wp_speed_old)) {
795
// old WP_SPEED parameter value was set so copy to new WP_SPEED
796
AP_Param::convert_old_parameter(&wp_speed_old_info, 1.0f);
797
} else {
798
// copy CRUISE_SPEED to new WP_SPEED
799
AP_Param::convert_old_parameter(&cruise_speed_info, 1.0f);
800
}
801
802
// attitude control FF and FILT parameter changes for Rover-3.6
803
const AP_Param::ConversionInfo ff_and_filt_conversion_info[] = {
804
{ Parameters::k_param_g2, 24650, AP_PARAM_FLOAT, "ATC_STR_RAT_FLTE" },
805
{ Parameters::k_param_g2, 28746, AP_PARAM_FLOAT, "ATC_STR_RAT_FF" },
806
{ Parameters::k_param_g2, 24714, AP_PARAM_FLOAT, "ATC_SPEED_FLTE" },
807
{ Parameters::k_param_g2, 28810, AP_PARAM_FLOAT, "ATC_SPEED_FF" },
808
{ Parameters::k_param_g2, 25226, AP_PARAM_FLOAT, "ATC_BAL_FLTE" },
809
{ Parameters::k_param_g2, 29322, AP_PARAM_FLOAT, "ATC_BAL_FF" },
810
{ Parameters::k_param_g2, 25354, AP_PARAM_FLOAT, "ATC_SAIL_FLTE" },
811
{ Parameters::k_param_g2, 29450, AP_PARAM_FLOAT, "ATC_SAIL_FF" },
812
};
813
AP_Param::convert_old_parameters(&ff_and_filt_conversion_info[0], ARRAY_SIZE(ff_and_filt_conversion_info));
814
815
// configure safety switch to allow stopping the motors while armed
816
#if HAL_HAVE_SAFETY_SWITCH
817
AP_Param::set_default_by_name("BRD_SAFETYOPTION", AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_OFF|
818
AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_ON|
819
AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_ARMED);
820
#endif
821
822
static const AP_Param::G2ObjectConversion g2_conversions[] {
823
#if AP_AIRSPEED_ENABLED
824
// PARAMETER_CONVERSION - Added: JAN-2022
825
{ &airspeed, airspeed.var_info, 37 },
826
#endif
827
#if AP_AIS_ENABLED
828
// PARAMETER_CONVERSION - Added: MAR-2022
829
{ &ais, ais.var_info, 50 },
830
#endif
831
#if AP_FENCE_ENABLED
832
// PARAMETER_CONVERSION - Added: Mar-2022
833
{ &fence, fence.var_info, 17 },
834
#endif
835
#if AP_STATS_ENABLED
836
// PARAMETER_CONVERSION - Added: Jan-2024 for Rover-4.6
837
{ &stats, stats.var_info, 1 },
838
#endif
839
#if AP_SCRIPTING_ENABLED
840
// PARAMETER_CONVERSION - Added: Jan-2024 for Rover-4.6
841
{ &scripting, scripting.var_info, 41 },
842
#endif
843
#if AP_GRIPPER_ENABLED
844
// PARAMETER_CONVERSION - Added: Feb-2024 for Copter-4.6
845
{ &gripper, gripper.var_info, 39 },
846
#endif
847
};
848
849
AP_Param::convert_g2_objects(&g2, g2_conversions, ARRAY_SIZE(g2_conversions));
850
851
// PARAMETER_CONVERSION - Added: Feb-2024 for Rover-4.6
852
#if HAL_LOGGING_ENABLED
853
AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, true);
854
#endif
855
856
// PARAMETER_CONVERSION - Added: July-2025 for ArduPilot-4.7
857
#if AP_RPM_ENABLED
858
AP_Param::convert_class(g.k_param_rpm_sensor_old, &rpm_sensor, rpm_sensor.var_info, 0, true, true);
859
#endif
860
861
static const AP_Param::TopLevelObjectConversion toplevel_conversions[] {
862
#if AP_SERIALMANAGER_ENABLED
863
// PARAMETER_CONVERSION - Added: Feb-2024 for Rover-4.6
864
{ &serial_manager, serial_manager.var_info, Parameters::k_param_serial_manager_old },
865
#endif
866
};
867
868
AP_Param::convert_toplevel_objects(toplevel_conversions, ARRAY_SIZE(toplevel_conversions));
869
870
#if HAL_GCS_ENABLED
871
// Move parameters into new MAV_ parameter namespace
872
// PARAMETER_CONVERSION - Added: Mar-2025 for ArduPilot-4.7
873
{
874
static const AP_Param::ConversionInfo gcs_conversion_info[] {
875
{ Parameters::k_param_sysid_this_mav_old, 0, AP_PARAM_INT16, "MAV_SYSID" },
876
{ Parameters::k_param_sysid_my_gcs_old, 0, AP_PARAM_INT16, "MAV_GCS_SYSID" },
877
{ Parameters::k_param_g2, 2, AP_PARAM_INT8, "MAV_OPTIONS" },
878
{ Parameters::k_param_telem_delay_old, 0, AP_PARAM_INT8, "MAV_TELEM_DELAY" },
879
};
880
AP_Param::convert_old_parameters(&gcs_conversion_info[0], ARRAY_SIZE(gcs_conversion_info));
881
}
882
#endif // HAL_GCS_ENABLED
883
884
}
885
886