CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduSub/Parameters.h
Views: 1798
1
#pragma once
2
3
#define AP_PARAM_VEHICLE_NAME sub
4
5
#include <AP_Common/AP_Common.h>
6
7
#include <AP_Arming/AP_Arming.h>
8
9
// Global parameter class.
10
//
11
class Parameters {
12
public:
13
// The version of the layout as described by the parameter enum.
14
//
15
// When changing the parameter enum in an incompatible fashion, this
16
// value should be incremented by one.
17
//
18
// The increment will prevent old parameters from being used incorrectly
19
// by newer code.
20
//
21
static const uint16_t k_format_version = 1;
22
23
// Parameter identities.
24
//
25
// The enumeration defined here is used to ensure that every parameter
26
// or parameter group has a unique ID number. This number is used by
27
// AP_Param to store and locate parameters in EEPROM.
28
//
29
// Note that entries without a number are assigned the next number after
30
// the entry preceding them. When adding new entries, ensure that they
31
// don't overlap.
32
//
33
// Try to group related variables together, and assign them a set
34
// range in the enumeration. Place these groups in numerical order
35
// at the end of the enumeration.
36
//
37
// WARNING: Care should be taken when editing this enumeration as the
38
// AP_Param load/save code depends on the values here to identify
39
// variables saved in EEPROM.
40
//
41
//
42
enum {
43
// Layout version number, always key zero.
44
//
45
k_param_format_version = 0,
46
k_param_software_type, // unused
47
48
k_param_g2, // 2nd block of parameters
49
50
k_param_sitl, // Simulation
51
52
// Telemetry
53
k_param_gcs0 = 10,
54
k_param_gcs1,
55
k_param_gcs2,
56
k_param_gcs3,
57
k_param_sysid_this_mav,
58
k_param_sysid_my_gcs,
59
60
// Hardware/Software configuration
61
k_param_BoardConfig = 20, // Board configuration (Pixhawk/Linux/etc)
62
k_param_scheduler, // Scheduler (for debugging/perf_info)
63
k_param_logger, // AP_Logger Logging
64
k_param_serial_manager_old, // Serial ports, AP_SerialManager
65
k_param_notify, // Notify Library, AP_Notify
66
k_param_arming = 26, // Arming checks
67
k_param_can_mgr,
68
69
// Sensor objects
70
k_param_ins = 30, // AP_InertialSensor
71
k_param_compass, // Compass
72
k_param_barometer, // Barometer/Depth Sensor
73
k_param_battery, // AP_BattMonitor
74
k_param_leak_detector, // Leak Detector
75
k_param_rangefinder, // Rangefinder
76
k_param_gps, // GPS
77
k_param_optflow, // Optical Flow
78
79
80
// Navigation libraries
81
k_param_ahrs = 50, // AHRS
82
k_param_NavEKF, // Extended Kalman Filter Inertial Navigation // remove
83
k_param_NavEKF2, // EKF2
84
k_param_attitude_control, // Attitude Control
85
k_param_pos_control, // Position Control
86
k_param_wp_nav, // Waypoint navigation
87
k_param_mission, // Mission library
88
k_param_fence_old, // only used for conversion
89
k_param_terrain, // Terrain database
90
k_param_rally, // Disabled
91
k_param_circle_nav, // Disabled
92
k_param_avoid, // Relies on proximity and fence
93
k_param_NavEKF3,
94
k_param_loiter_nav,
95
96
97
// Other external hardware interfaces
98
k_param_motors = 65, // Motors
99
k_param_relay, // Relay
100
k_param_camera, // Camera
101
k_param_camera_mount, // Camera gimbal
102
103
104
// RC_Channel settings (deprecated)
105
k_param_rc_1_old = 75,
106
k_param_rc_2_old,
107
k_param_rc_3_old,
108
k_param_rc_4_old,
109
k_param_rc_5_old,
110
k_param_rc_6_old,
111
k_param_rc_7_old,
112
k_param_rc_8_old,
113
k_param_rc_9_old,
114
k_param_rc_10_old,
115
k_param_rc_11_old,
116
k_param_rc_12_old,
117
k_param_rc_13_old,
118
k_param_rc_14_old,
119
120
// Joystick gain parameters
121
k_param_gain_default,
122
k_param_maxGain,
123
k_param_minGain,
124
k_param_numGainSettings,
125
k_param_cam_tilt_step, // deprecated
126
k_param_lights_step, // deprecated
127
128
// Joystick button mapping parameters
129
k_param_jbtn_0 = 95,
130
k_param_jbtn_1,
131
k_param_jbtn_2,
132
k_param_jbtn_3,
133
k_param_jbtn_4,
134
k_param_jbtn_5,
135
k_param_jbtn_6,
136
k_param_jbtn_7,
137
k_param_jbtn_8,
138
k_param_jbtn_9,
139
k_param_jbtn_10,
140
k_param_jbtn_11,
141
k_param_jbtn_12,
142
k_param_jbtn_13,
143
k_param_jbtn_14,
144
k_param_jbtn_15,
145
146
// 16 more for MANUAL_CONTROL extensions
147
k_param_jbtn_16,
148
k_param_jbtn_17,
149
k_param_jbtn_18,
150
k_param_jbtn_19,
151
k_param_jbtn_20,
152
k_param_jbtn_21,
153
k_param_jbtn_22,
154
k_param_jbtn_23,
155
k_param_jbtn_24,
156
k_param_jbtn_25,
157
k_param_jbtn_26,
158
k_param_jbtn_27,
159
k_param_jbtn_28,
160
k_param_jbtn_29,
161
k_param_jbtn_30,
162
k_param_jbtn_31,
163
164
// PID Controllers
165
k_param_p_pos_xy = 126, // deprecated
166
k_param_p_alt_hold, // deprecated
167
k_param_pi_vel_xy, // deprecated
168
k_param_p_vel_z, // deprecated
169
k_param_pid_accel_z, // deprecated
170
171
172
// Failsafes
173
k_param_failsafe_gcs = 140,
174
k_param_failsafe_leak, // leak failsafe behavior
175
k_param_failsafe_pressure, // internal pressure failsafe behavior
176
k_param_failsafe_pressure_max, // maximum internal pressure in pascal before failsafe is triggered
177
k_param_failsafe_temperature, // internal temperature failsafe behavior
178
k_param_failsafe_temperature_max, // maximum internal temperature in degrees C before failsafe is triggered
179
k_param_failsafe_terrain, // terrain failsafe behavior
180
k_param_fs_ekf_thresh,
181
k_param_fs_ekf_action,
182
k_param_fs_crash_check,
183
k_param_failsafe_battery_enabled, // unused - moved to AP_BattMonitor
184
k_param_fs_batt_mah, // unused - moved to AP_BattMonitor
185
k_param_fs_batt_voltage, // unused - moved to AP_BattMonitor
186
k_param_failsafe_pilot_input,
187
k_param_failsafe_pilot_input_timeout,
188
k_param_failsafe_gcs_timeout,
189
190
191
// Misc Sub settings
192
k_param_log_bitmask = 165,
193
k_param_angle_max = 167,
194
k_param_rangefinder_gain, // deprecated
195
k_param_wp_yaw_behavior = 170,
196
k_param_xtrack_angle_limit, // Angle limit for crosstrack correction in Auto modes (degrees)
197
k_param_pilot_speed_up, // renamed from k_param_pilot_velocity_z_max
198
k_param_pilot_accel_z,
199
k_param_compass_enabled_deprecated,
200
k_param_surface_depth,
201
k_param_rc_speed, // Main output pwm frequency
202
k_param_gcs_pid_mask = 178,
203
k_param_throttle_filt,
204
k_param_throttle_deadzone, // Used in auto-throttle modes
205
k_param_terrain_follow = 182, // deprecated
206
k_param_rc_feel_rp,
207
k_param_throttle_gain,
208
k_param_cam_tilt_center, // deprecated
209
k_param_frame_configuration,
210
211
// Acro Mode parameters
212
k_param_acro_yaw_p = 220, // Used in all modes for get_pilot_desired_yaw_rate
213
k_param_acro_trainer,
214
k_param_acro_expo,
215
k_param_acro_rp_p,
216
k_param_acro_balance_roll,
217
k_param_acro_balance_pitch,
218
219
// RPM Sensor
220
k_param_rpm_sensor = 232, // Disabled
221
222
// RC_Mapper Library
223
k_param_rcmap, // Disabled
224
225
k_param_gcs4,
226
k_param_gcs5,
227
k_param_gcs6,
228
229
k_param_cam_slew_limit = 237, // deprecated
230
k_param_lights_steps,
231
k_param_pilot_speed_dn,
232
k_param_rangefinder_signal_min,
233
k_param_surftrak_depth,
234
235
k_param_vehicle = 257, // vehicle common block of parameters
236
};
237
238
AP_Int16 format_version;
239
240
// Telemetry control
241
//
242
AP_Int16 sysid_this_mav;
243
AP_Int16 sysid_my_gcs;
244
245
AP_Float throttle_filt;
246
247
#if AP_RANGEFINDER_ENABLED
248
AP_Int8 rangefinder_signal_min; // minimum signal quality for good rangefinder readings
249
AP_Float surftrak_depth; // surftrak will try to keep sub below this depth
250
#endif
251
252
AP_Int8 failsafe_leak; // leak detection failsafe behavior
253
AP_Int8 failsafe_gcs; // ground station failsafe behavior
254
AP_Int8 failsafe_pressure;
255
AP_Int8 failsafe_temperature;
256
AP_Int32 failsafe_pressure_max;
257
AP_Int8 failsafe_temperature_max;
258
AP_Int8 failsafe_terrain;
259
AP_Int8 failsafe_pilot_input; // pilot input failsafe behavior
260
AP_Float failsafe_pilot_input_timeout;
261
AP_Float failsafe_gcs_timeout; // ground station failsafe timeout (seconds)
262
263
AP_Int8 xtrack_angle_limit;
264
265
AP_Int8 wp_yaw_behavior; // controls how the autopilot controls yaw during missions
266
AP_Int8 rc_feel_rp; // controls vehicle response to user input with 0 being extremely soft and 100 begin extremely crisp
267
268
// Waypoints
269
//
270
AP_Int16 pilot_speed_up; // maximum vertical ascending velocity the pilot may request
271
AP_Int16 pilot_speed_dn; // maximum vertical descending velocity the pilot may request
272
AP_Int16 pilot_accel_z; // vertical acceleration the pilot may request
273
274
// Throttle
275
//
276
AP_Int16 throttle_deadzone;
277
278
// Misc
279
//
280
AP_Int32 log_bitmask;
281
282
AP_Int8 fs_ekf_action;
283
AP_Int8 fs_crash_check;
284
AP_Float fs_ekf_thresh;
285
AP_Int16 gcs_pid_mask;
286
287
AP_Int16 rc_speed; // speed of fast RC Channels in Hz
288
289
AP_Float gain_default;
290
AP_Float maxGain;
291
AP_Float minGain;
292
AP_Int8 numGainSettings;
293
AP_Float throttle_gain;
294
295
AP_Int16 lights_steps;
296
297
// Joystick button parameters
298
JSButton jbtn_0;
299
JSButton jbtn_1;
300
JSButton jbtn_2;
301
JSButton jbtn_3;
302
JSButton jbtn_4;
303
JSButton jbtn_5;
304
JSButton jbtn_6;
305
JSButton jbtn_7;
306
JSButton jbtn_8;
307
JSButton jbtn_9;
308
JSButton jbtn_10;
309
JSButton jbtn_11;
310
JSButton jbtn_12;
311
JSButton jbtn_13;
312
JSButton jbtn_14;
313
JSButton jbtn_15;
314
// 16 - 31 from manual_control extension
315
JSButton jbtn_16;
316
JSButton jbtn_17;
317
JSButton jbtn_18;
318
JSButton jbtn_19;
319
JSButton jbtn_20;
320
JSButton jbtn_21;
321
JSButton jbtn_22;
322
JSButton jbtn_23;
323
JSButton jbtn_24;
324
JSButton jbtn_25;
325
JSButton jbtn_26;
326
JSButton jbtn_27;
327
JSButton jbtn_28;
328
JSButton jbtn_29;
329
JSButton jbtn_30;
330
JSButton jbtn_31;
331
332
// Acro parameters
333
AP_Float acro_rp_p;
334
AP_Float acro_yaw_p;
335
AP_Float acro_balance_roll;
336
AP_Float acro_balance_pitch;
337
AP_Int8 acro_trainer;
338
AP_Float acro_expo;
339
340
AP_Float surface_depth;
341
AP_Int8 frame_configuration;
342
343
// Note: keep initializers here in the same order as they are declared
344
// above.
345
Parameters()
346
{
347
}
348
};
349
350
/*
351
2nd block of parameters, to avoid going past 256 top level keys
352
*/
353
class ParametersG2 {
354
public:
355
ParametersG2(void);
356
357
// var_info for holding Parameter information
358
static const struct AP_Param::GroupInfo var_info[];
359
360
#if HAL_PROXIMITY_ENABLED
361
// proximity (aka object avoidance) library
362
AP_Proximity proximity;
363
#endif
364
365
// RC input channels
366
RC_Channels_Sub rc_channels;
367
368
// control over servo output ranges
369
SRV_Channels servo_channels;
370
371
AP_Float backup_origin_lat;
372
AP_Float backup_origin_lon;
373
AP_Float backup_origin_alt;
374
};
375
376
extern const AP_Param::Info var_info[];
377
378
// Sub-specific default parameters
379
static const struct AP_Param::defaults_table_struct defaults_table[] = {
380
{ "BRD_SAFETY_DEFLT", 0 },
381
{ "ARMING_CHECK", AP_Arming::ARMING_CHECK_RC |
382
AP_Arming::ARMING_CHECK_VOLTAGE |
383
AP_Arming::ARMING_CHECK_BATTERY},
384
{ "CIRCLE_RATE", 2.0f},
385
{ "ATC_ACCEL_Y_MAX", 110000.0f},
386
{ "ATC_RATE_Y_MAX", 180.0f},
387
{ "RC3_TRIM", 1100},
388
{ "COMPASS_OFFS_MAX", 1000},
389
{ "INS_GYR_CAL", 0},
390
#if HAL_MOUNT_ENABLED
391
{ "MNT1_TYPE", 1},
392
{ "MNT1_DEFLT_MODE", MAV_MOUNT_MODE_RC_TARGETING},
393
{ "MNT1_RC_RATE", 30},
394
#endif
395
{ "RC7_OPTION", 214}, // MOUNT1_YAW
396
{ "RC8_OPTION", 213}, // MOUNT1_PITCH
397
{ "MOT_PWM_MIN", 1100},
398
{ "MOT_PWM_MAX", 1900},
399
{ "PSC_JERK_Z", 50.0f},
400
{ "WPNAV_SPEED", 100.0f},
401
{ "PILOT_SPEED_UP", 100.0f},
402
{ "PSC_VELXY_P", 6.0f},
403
{ "EK3_SRC1_VELZ", 0},
404
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIGATOR
405
#if AP_BARO_PROBE_EXT_PARAMETER_ENABLED
406
{ "BARO_PROBE_EXT", 0},
407
#endif
408
{ "BATT_MONITOR", 4},
409
{ "BATT_CAPACITY", 0},
410
{ "LEAK1_PIN", 27},
411
{ "SCHED_LOOP_RATE", 200},
412
{ "SERVO13_FUNCTION", 59}, // k_rcin9, lights 1
413
{ "SERVO14_FUNCTION", 60}, // k_rcin10, lights 2
414
{ "SERVO16_FUNCTION", 7}, // k_mount_tilt
415
{ "SERVO16_REVERSED", 1},
416
#else
417
#if AP_BARO_PROBE_EXT_PARAMETER_ENABLED
418
{ "BARO_PROBE_EXT", 768},
419
#endif
420
{ "SERVO9_FUNCTION", 59}, // k_rcin9, lights 1
421
{ "SERVO10_FUNCTION", 7}, // k_mount_tilt
422
#endif
423
};
424
425