forked from ArduPilot/ardupilot
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathParameters.h
169 lines (145 loc) · 4.91 KB
/
Parameters.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
#pragma once
#include <AP_Common/AP_Common.h>
// Global parameter class.
//
class Parameters {
public:
/*
* The value of k_format_version determines whether the existing
* eeprom data is considered valid. You should only change this
* value under the following circumstances:
*
* 1) the meaning of an existing eeprom parameter changes
*
* 2) the value of an existing k_param_* enum value changes
*
* Adding a new parameter should _not_ require a change to
* k_format_version except under special circumstances. If you
* change it anyway then all ArduPlane users will need to reload all
* their parameters. We want that to be an extremely rare
* thing. Please do not just change it "just in case".
*
* To determine if a k_param_* value has changed, use the rules of
* C++ enums to work out the value of the neighboring enum
* values. If you don't know the C++ enum rules then please ask for
* help.
*/
//////////////////////////////////////////////////////////////////
// STOP!!! DO NOT CHANGE THIS VALUE UNTIL YOU FULLY UNDERSTAND THE
// COMMENTS ABOVE. IF UNSURE, ASK ANOTHER DEVELOPER!!!
static const uint16_t k_format_version = 1;
//////////////////////////////////////////////////////////////////
enum {
// Layout version number, always key zero.
//
k_param_format_version = 0,
k_param_software_type, // deprecated
k_param_gcs0 = 100, // stream rates for uartA
k_param_gcs1, // stream rates for uartC
k_param_sysid_this_mav,
k_param_sysid_my_gcs,
k_param_serial0_baud, // deprecated
k_param_serial1_baud, // deprecated
k_param_imu,
k_param_compass_enabled,
k_param_compass,
k_param_ahrs, // AHRS group
k_param_barometer,
k_param_scheduler,
k_param_ins,
k_param_sitl,
k_param_pidPitch_old, // deprecated
k_param_pidYaw_old, // deprecated
k_param_gcs2, // stream rates for uartD
k_param_serial2_baud, // deprecated
k_param_yaw_slew_time,
k_param_pitch_slew_time,
k_param_min_reverse_time,
k_param_start_latitude,
k_param_start_longitude,
k_param_startup_delay,
k_param_BoardConfig,
k_param_gps,
k_param_scan_speed,
k_param_proxy_mode_unused, // deprecated
k_param_servo_pitch_type,
k_param_onoff_yaw_rate,
k_param_onoff_pitch_rate,
k_param_onoff_yaw_mintime,
k_param_onoff_pitch_mintime,
k_param_yaw_trim,
k_param_pitch_trim,
k_param_yaw_range,
k_param_pitch_range, //deprecated
k_param_distance_min,
k_param_sysid_target, // 138
k_param_gcs3, // stream rates for fourth MAVLink port
k_param_log_bitmask, // 140
k_param_notify,
k_param_BoardConfig_CAN,
k_param_battery,
//
// 150: Telemetry control
//
k_param_serial_manager, // serial manager library
k_param_servo_yaw_type,
k_param_alt_source,
k_param_mavlink_update_rate,
k_param_pitch_min,
k_param_pitch_max,
//
// 200 : Radio settings
//
k_param_channel_yaw_old = 200,
k_param_channel_pitch_old,
k_param_pidPitch2Srv,
k_param_pidYaw2Srv,
k_param_rc_channels,
k_param_servo_channels,
//
// 220: Waypoint data
//
k_param_command_total = 220,
// 254,255: reserved
};
AP_Int16 format_version;
// Telemetry control
//
AP_Int16 sysid_this_mav;
AP_Int16 sysid_my_gcs;
AP_Int16 sysid_target;
AP_Int8 compass_enabled;
AP_Float yaw_slew_time;
AP_Float pitch_slew_time;
AP_Float min_reverse_time;
AP_Float scan_speed;
AP_Float start_latitude;
AP_Float start_longitude;
AP_Float startup_delay;
AP_Int8 servo_pitch_type;
AP_Int8 servo_yaw_type;
AP_Int8 alt_source;
AP_Int8 mavlink_update_rate;
AP_Float onoff_yaw_rate;
AP_Float onoff_pitch_rate;
AP_Float onoff_yaw_mintime;
AP_Float onoff_pitch_mintime;
AP_Float yaw_trim;
AP_Float pitch_trim;
AP_Int16 yaw_range; // yaw axis total range of motion in degrees
AP_Int16 distance_min; // target's must be at least this distance from tracker to be tracked
AP_Int16 pitch_min;
AP_Int16 pitch_max;
// Waypoints
//
AP_Int8 command_total; // 1 if HOME is set
AP_Int32 log_bitmask;
// AC_PID controllers
AC_PID pidPitch2Srv;
AC_PID pidYaw2Srv;
Parameters() :
pidPitch2Srv(0.2, 0, 0.05f, 4000.0f, 0.1, 0.02f),
pidYaw2Srv (0.2, 0, 0.05f, 4000.0f, 0.1, 0.02f)
{}
};
extern const AP_Param::Info var_info[];