PX4 Firmware
PX4 Autopilot Software http://px4.io
params.c
Go to the documentation of this file.
1 #include <parameters/param.h>
2 
3 // 16 is max name length
4 
5 /**
6  * Optical flow z offset from center
7  *
8  * @group Local Position Estimator
9  * @unit m
10  * @min -1
11  * @max 1
12  * @decimal 3
13  */
14 PARAM_DEFINE_FLOAT(LPE_FLW_OFF_Z, 0.0f);
15 
16 /**
17  * Optical flow scale
18  *
19  * @group Local Position Estimator
20  * @unit m
21  * @min 0.1
22  * @max 10.0
23  * @decimal 3
24  */
25 PARAM_DEFINE_FLOAT(LPE_FLW_SCALE, 1.3f);
26 
27 /**
28  * Optical flow rotation (roll/pitch) noise gain
29  *
30  * @group Local Position Estimator
31  * @unit m/s / (rad)
32  * @min 0.1
33  * @max 10.0
34  * @decimal 3
35  */
36 PARAM_DEFINE_FLOAT(LPE_FLW_R, 7.0f);
37 
38 /**
39  * Optical flow angular velocity noise gain
40  *
41  * @group Local Position Estimator
42  * @unit m/s / (rad/s)
43  * @min 0.0
44  * @max 10.0
45  * @decimal 3
46  */
47 PARAM_DEFINE_FLOAT(LPE_FLW_RR, 7.0f);
48 
49 /**
50  * Optical flow minimum quality threshold
51  *
52  * @group Local Position Estimator
53  * @min 0
54  * @max 255
55  * @decimal 0
56  */
57 PARAM_DEFINE_INT32(LPE_FLW_QMIN, 150);
58 
59 /**
60  * Sonar z standard deviation.
61  *
62  * @group Local Position Estimator
63  * @unit m
64  * @min 0.01
65  * @max 1
66  * @decimal 3
67  */
68 PARAM_DEFINE_FLOAT(LPE_SNR_Z, 0.05f);
69 
70 /**
71  * Sonar z offset from center of vehicle +down
72  *
73  * @group Local Position Estimator
74  * @unit m
75  * @min -1
76  * @max 1
77  * @decimal 3
78  */
79 PARAM_DEFINE_FLOAT(LPE_SNR_OFF_Z, 0.00f);
80 
81 /**
82  * Lidar z standard deviation.
83  *
84  * @group Local Position Estimator
85  * @unit m
86  * @min 0.01
87  * @max 1
88  * @decimal 3
89  */
90 PARAM_DEFINE_FLOAT(LPE_LDR_Z, 0.03f);
91 
92 /**
93  * Lidar z offset from center of vehicle +down
94  *
95  * @group Local Position Estimator
96  * @unit m
97  * @min -1
98  * @max 1
99  * @decimal 3
100  */
101 PARAM_DEFINE_FLOAT(LPE_LDR_OFF_Z, 0.00f);
102 
103 /**
104  * Accelerometer xy noise density
105  *
106  * Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz)
107  *
108  * Larger than data sheet to account for tilt error.
109  *
110  * @group Local Position Estimator
111  * @unit m/s^2/sqrt(Hz)
112  * @min 0.00001
113  * @max 2
114  * @decimal 4
115  */
116 PARAM_DEFINE_FLOAT(LPE_ACC_XY, 0.012f);
117 
118 /**
119  * Accelerometer z noise density
120  *
121  * Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz)
122  *
123  * @group Local Position Estimator
124  * @unit m/s^2/sqrt(Hz)
125  * @min 0.00001
126  * @max 2
127  * @decimal 4
128  */
129 PARAM_DEFINE_FLOAT(LPE_ACC_Z, 0.02f);
130 
131 /**
132  * Barometric presssure altitude z standard deviation.
133  *
134  * @group Local Position Estimator
135  * @unit m
136  * @min 0.01
137  * @max 100
138  * @decimal 2
139  */
140 PARAM_DEFINE_FLOAT(LPE_BAR_Z, 3.0f);
141 
142 /**
143  * GPS delay compensaton
144  *
145  * @group Local Position Estimator
146  * @unit sec
147  * @min 0
148  * @max 0.4
149  * @decimal 2
150  */
151 PARAM_DEFINE_FLOAT(LPE_GPS_DELAY, 0.29f);
152 
153 
154 /**
155  * Minimum GPS xy standard deviation, uses reported EPH if greater.
156  *
157  * @group Local Position Estimator
158  * @unit m
159  * @min 0.01
160  * @max 5
161  * @decimal 2
162  */
163 PARAM_DEFINE_FLOAT(LPE_GPS_XY, 1.0f);
164 
165 /**
166  * Minimum GPS z standard deviation, uses reported EPV if greater.
167  *
168  * @group Local Position Estimator
169  * @unit m
170  * @min 0.01
171  * @max 200
172  * @decimal 2
173  */
174 PARAM_DEFINE_FLOAT(LPE_GPS_Z, 3.0f);
175 
176 /**
177  * GPS xy velocity standard deviation.
178  * EPV used if greater than this value.
179  *
180  * @group Local Position Estimator
181  * @unit m/s
182  * @min 0.01
183  * @max 2
184  * @decimal 3
185  */
186 PARAM_DEFINE_FLOAT(LPE_GPS_VXY, 0.25f);
187 
188 /**
189  * GPS z velocity standard deviation.
190  *
191  * @group Local Position Estimator
192  * @unit m/s
193  * @min 0.01
194  * @max 2
195  * @decimal 3
196  */
197 PARAM_DEFINE_FLOAT(LPE_GPS_VZ, 0.25f);
198 
199 /**
200  * Max EPH allowed for GPS initialization
201  *
202  * @group Local Position Estimator
203  * @unit m
204  * @min 1.0
205  * @max 5.0
206  * @decimal 3
207  */
208 PARAM_DEFINE_FLOAT(LPE_EPH_MAX, 3.0f);
209 
210 /**
211  * Max EPV allowed for GPS initialization
212  *
213  * @group Local Position Estimator
214  * @unit m
215  * @min 1.0
216  * @max 5.0
217  * @decimal 3
218  */
219 PARAM_DEFINE_FLOAT(LPE_EPV_MAX, 5.0f);
220 
221 /**
222  * Vision delay compensaton.
223  *
224  * Set to zero to enable automatic compensation from measurement timestamps
225  *
226  * @group Local Position Estimator
227  * @unit sec
228  * @min 0
229  * @max 0.1
230  * @decimal 2
231  */
232 PARAM_DEFINE_FLOAT(LPE_VIS_DELAY, 0.1f);
233 
234 /**
235  * Vision xy standard deviation.
236  *
237  * @group Local Position Estimator
238  * @unit m
239  * @min 0.01
240  * @max 1
241  * @decimal 3
242  */
243 PARAM_DEFINE_FLOAT(LPE_VIS_XY, 0.1f);
244 
245 /**
246  * Vision z standard deviation.
247  *
248  * @group Local Position Estimator
249  * @unit m
250  * @min 0.01
251  * @max 100
252  * @decimal 3
253  */
254 PARAM_DEFINE_FLOAT(LPE_VIS_Z, 0.5f);
255 
256 /**
257  * Vicon position standard deviation.
258  *
259  * @group Local Position Estimator
260  * @unit m
261  * @min 0.0001
262  * @max 1
263  * @decimal 4
264  */
265 PARAM_DEFINE_FLOAT(LPE_VIC_P, 0.001f);
266 
267 /**
268  * Position propagation noise density
269  *
270  * Increase to trust measurements more.
271  * Decrease to trust model more.
272  *
273  * @group Local Position Estimator
274  * @unit m/s/sqrt(Hz)
275  * @min 0
276  * @max 1
277  * @decimal 8
278  */
279 PARAM_DEFINE_FLOAT(LPE_PN_P, 0.1f);
280 
281 /**
282  * Velocity propagation noise density
283  *
284  * Increase to trust measurements more.
285  * Decrease to trust model more.
286  *
287  * @group Local Position Estimator
288  * @unit (m/s)/s/sqrt(Hz)
289  * @min 0
290  * @max 1
291  * @decimal 8
292  */
293 PARAM_DEFINE_FLOAT(LPE_PN_V, 0.1f);
294 
295 /**
296  * Accel bias propagation noise density
297  *
298  * @group Local Position Estimator
299  * @unit (m/s^2)/s/sqrt(Hz)
300  * @min 0
301  * @max 1
302  * @decimal 8
303  */
304 PARAM_DEFINE_FLOAT(LPE_PN_B, 1e-3f);
305 
306 /**
307  * Terrain random walk noise density, hilly/outdoor (0.1), flat/Indoor (0.001)
308  *
309  * @group Local Position Estimator
310  * @unit (m/s)/(sqrt(hz))
311  * @min 0
312  * @max 1
313  * @decimal 3
314  */
315 PARAM_DEFINE_FLOAT(LPE_PN_T, 0.001f);
316 
317 /**
318  * Terrain maximum percent grade, hilly/outdoor (100 = 45 deg), flat/Indoor (0 = 0 deg)
319  * Used to calculate increased terrain random walk nosie due to movement.
320  *
321  * @group Local Position Estimator
322  * @unit %
323  * @min 0
324  * @max 100
325  * @decimal 3
326  */
327 PARAM_DEFINE_FLOAT(LPE_T_MAX_GRADE, 1.0f);
328 
329 /**
330  * Flow gyro high pass filter cut off frequency
331  *
332  * @group Local Position Estimator
333  * @unit Hz
334  * @min 0
335  * @max 2
336  * @decimal 3
337  */
338 PARAM_DEFINE_FLOAT(LPE_FGYRO_HP, 0.001f);
339 
340 /**
341  * Enable publishing of a fake global position (e.g for AUTO missions using Optical Flow)
342  * by initializing the estimator to the LPE_LAT/LON parameters when global information is unavailable
343  *
344  * @group Local Position Estimator
345  * @min 0
346  * @max 1
347  */
348 PARAM_DEFINE_INT32(LPE_FAKE_ORIGIN, 0);
349 
350 /**
351  * Local origin latitude for nav w/o GPS
352  *
353  * @group Local Position Estimator
354  * @unit deg
355  * @min -90
356  * @max 90
357  * @decimal 8
358  */
359 PARAM_DEFINE_FLOAT(LPE_LAT, 47.397742f);
360 
361 /**
362  * Local origin longitude for nav w/o GPS
363  *
364  * @group Local Position Estimator
365  * @unit deg
366  * @min -180
367  * @max 180
368  * @decimal 8
369  */
370 PARAM_DEFINE_FLOAT(LPE_LON, 8.545594);
371 
372 /**
373  * Cut frequency for state publication
374  *
375  * @group Local Position Estimator
376  * @unit Hz
377  * @min 5
378  * @max 1000
379  * @decimal 0
380  */
381 PARAM_DEFINE_FLOAT(LPE_X_LP, 5.0f);
382 
383 /**
384  * Required velocity xy standard deviation to publish position
385  *
386  * @group Local Position Estimator
387  * @unit m/s
388  * @min 0.01
389  * @max 1.0
390  * @decimal 3
391  */
392 PARAM_DEFINE_FLOAT(LPE_VXY_PUB, 0.3f);
393 
394 /**
395  * Required z standard deviation to publish altitude/ terrain
396  *
397  * @group Local Position Estimator
398  * @unit m
399  * @min 0.3
400  * @max 5.0
401  * @decimal 1
402  */
403 PARAM_DEFINE_FLOAT(LPE_Z_PUB, 1.0f);
404 
405 /**
406  * Land detector z standard deviation
407  *
408  * @group Local Position Estimator
409  * @unit m
410  * @min 0.001
411  * @max 10.0
412  * @decimal 3
413  */
414 PARAM_DEFINE_FLOAT(LPE_LAND_Z, 0.03f);
415 
416 /**
417  * Land detector xy velocity standard deviation
418  *
419  * @group Local Position Estimator
420  * @unit m/s
421  * @min 0.01
422  * @max 10.0
423  * @decimal 3
424  */
425 PARAM_DEFINE_FLOAT(LPE_LAND_VXY, 0.05f);
426 
427 /**
428  * Minimum landing target standard covariance, uses reported covariance if greater.
429  *
430  * @group Local Position Estimator
431  * @unit m^2
432  * @min 0.0
433  * @max 10
434  * @decimal 2
435  */
436 PARAM_DEFINE_FLOAT(LPE_LT_COV, 0.0001f);
437 
438 /**
439  * Integer bitmask controlling data fusion
440  *
441  * Set bits in the following positions to enable:
442  * 0 : Set to true to fuse GPS data if available, also requires GPS for altitude init
443  * 1 : Set to true to fuse optical flow data if available
444  * 2 : Set to true to fuse vision position
445  * 3 : Set to true to enable landing target
446  * 4 : Set to true to fuse land detector
447  * 5 : Set to true to publish AGL as local position down component
448  * 6 : Set to true to enable flow gyro compensation
449  * 7 : Set to true to enable baro fusion
450  *
451  * default (145 - GPS, baro, land detector)
452  *
453  * @group Local Position Estimator
454  * @min 0
455  * @max 255
456  * @bit 0 fuse GPS, requires GPS for alt. init
457  * @bit 1 fuse optical flow
458  * @bit 2 fuse vision position
459  * @bit 3 fuse landing target
460  * @bit 4 fuse land detector
461  * @bit 5 pub agl as lpos down
462  * @bit 6 flow gyro compensation
463  * @bit 7 fuse baro
464  */
465 PARAM_DEFINE_INT32(LPE_FUSION, 145);
PARAM_DEFINE_INT32(GPS_DUMP_COMM, 0)
Dump GPS communication to a file.
Global flash based parameter store.
Vector< float, 6 > f(float t, const Matrix< float, 6, 1 > &, const Matrix< float, 3, 1 > &)
Definition: integration.cpp:8
PARAM_DEFINE_FLOAT(GPS_YAW_OFFSET, 0.f)
Heading/Yaw offset for dual antenna GPS.