APM:Libraries
AP_L1_Control.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 #include "AP_L1_Control.h"
3 
4 extern const AP_HAL::HAL& hal;
5 
6 // table of user settable parameters
8  // @Param: PERIOD
9  // @DisplayName: L1 control period
10  // @Description: Period in seconds of L1 tracking loop. This parameter is the primary control for agressiveness of turns in auto mode. This needs to be larger for less responsive airframes. The default of 20 is quite conservative, but for most RC aircraft will lead to reasonable flight. For smaller more agile aircraft a value closer to 15 is appropriate, or even as low as 10 for some very agile aircraft. When tuning, change this value in small increments, as a value that is much too small (say 5 or 10 below the right value) can lead to very radical turns, and a risk of stalling.
11  // @Units: s
12  // @Range: 1 60
13  // @Increment: 1
14  // @User: Standard
15  AP_GROUPINFO("PERIOD", 0, AP_L1_Control, _L1_period, 20),
16 
17  // @Param: DAMPING
18  // @DisplayName: L1 control damping ratio
19  // @Description: Damping ratio for L1 control. Increase this in increments of 0.05 if you are getting overshoot in path tracking. You should not need a value below 0.7 or above 0.85.
20  // @Range: 0.6 1.0
21  // @Increment: 0.05
22  // @User: Advanced
23  AP_GROUPINFO("DAMPING", 1, AP_L1_Control, _L1_damping, 0.75f),
24 
25  // @Param: XTRACK_I
26  // @DisplayName: L1 control crosstrack integrator gain
27  // @Description: Crosstrack error integrator gain. This gain is applied to the crosstrack error to ensure it converges to zero. Set to zero to disable. Smaller values converge slower, higher values will cause crosstrack error oscillation.
28  // @Range: 0 0.1
29  // @Increment: 0.01
30  // @User: Advanced
31  AP_GROUPINFO("XTRACK_I", 2, AP_L1_Control, _L1_xtrack_i_gain, 0.02),
32 
33  // @Param: LIM_BANK
34  // @DisplayName: Loiter Radius Bank Angle Limit
35  // @Description: The sealevel bank angle limit for a continous loiter. (Used to calculate airframe loading limits at higher altitudes). Setting to 0, will instead just scale the loiter radius directly
36  // @Units: deg
37  // @Range: 0 89
38  // @User: Advanced
39  AP_GROUPINFO_FRAME("LIM_BANK", 3, AP_L1_Control, _loiter_bank_limit, 0.0f, AP_PARAM_FRAME_PLANE),
40 
42 };
43 
44 //Bank angle command based on angle between aircraft velocity vector and reference vector to path.
45 //S. Park, J. Deyst, and J. P. How, "A New Nonlinear Guidance Logic for Trajectory Tracking,"
46 //Proceedings of the AIAA Guidance, Navigation and Control
47 //Conference, Aug 2004. AIAA-2004-4900.
48 //Modified to use PD control for circle tracking to enable loiter radius less than L1 length
49 //Modified to enable period and damping of guidance loop to be set explicitly
50 //Modified to provide explicit control over capture angle
51 
52 
53 /*
54  Wrap AHRS yaw if in reverse - radians
55  */
57 {
58  if (_reverse) {
59  return wrap_PI(M_PI + _ahrs.yaw);
60  }
61  return _ahrs.yaw;
62 }
63 
64 /*
65  Wrap AHRS yaw sensor if in reverse - centi-degress
66  */
68 {
69  if (_reverse) {
70  return wrap_180_cd(18000 + _ahrs.yaw_sensor);
71  }
72  return _ahrs.yaw_sensor;
73 }
74 
75 /*
76  return the bank angle needed to achieve tracking from the last
77  update_*() operation
78  */
79 int32_t AP_L1_Control::nav_roll_cd(void) const
80 {
81  float ret;
82  ret = cosf(_ahrs.pitch)*degrees(atanf(_latAccDem * 0.101972f) * 100.0f); // 0.101972 = 1/9.81
83  ret = constrain_float(ret, -9000, 9000);
84  return ret;
85 }
86 
87 /*
88  return the lateral acceleration needed to achieve tracking from the last
89  update_*() operation
90  */
92 {
93  return _latAccDem;
94 }
95 
96 int32_t AP_L1_Control::nav_bearing_cd(void) const
97 {
99 }
100 
102 {
104 }
105 
107 {
109 }
110 
111 /*
112  this is the turn distance assuming a 90 degree turn
113  */
114 float AP_L1_Control::turn_distance(float wp_radius) const
115 {
116  wp_radius *= sq(_ahrs.get_EAS2TAS());
117  return MIN(wp_radius, _L1_dist);
118 }
119 
120 /*
121  this approximates the turn distance for a given turn angle. If the
122  turn_angle is > 90 then a 90 degree turn distance is used, otherwise
123  the turn distance is reduced linearly.
124  This function allows straight ahead mission legs to avoid thinking
125  they have reached the waypoint early, which makes things like camera
126  trigger and ball drop at exact positions under mission control much easier
127  */
128 float AP_L1_Control::turn_distance(float wp_radius, float turn_angle) const
129 {
130  float distance_90 = turn_distance(wp_radius);
131  turn_angle = fabsf(turn_angle);
132  if (turn_angle >= 90) {
133  return distance_90;
134  }
135  return distance_90 * turn_angle / 90.0f;
136 }
137 
138 float AP_L1_Control::loiter_radius(const float radius) const
139 {
140  // prevent an insane loiter bank limit
141  float sanitized_bank_limit = constrain_float(_loiter_bank_limit, 0.0f, 89.0f);
142  float lateral_accel_sea_level = tanf(radians(sanitized_bank_limit)) * GRAVITY_MSS;
143 
144  float nominal_velocity_sea_level;
145  if(_spdHgtControl == nullptr) {
146  nominal_velocity_sea_level = 0.0f;
147  } else {
148  nominal_velocity_sea_level = _spdHgtControl->get_target_airspeed();
149  }
150 
151  float eas2tas_sq = sq(_ahrs.get_EAS2TAS());
152 
153  if (is_zero(sanitized_bank_limit) || is_zero(nominal_velocity_sea_level) ||
154  is_zero(lateral_accel_sea_level)) {
155  // Missing a sane input for calculating the limit, or the user has
156  // requested a straight scaling with altitude. This will always vary
157  // with the current altitude, but will at least protect the airframe
158  return radius * eas2tas_sq;
159  } else {
160  float sea_level_radius = sq(nominal_velocity_sea_level) / lateral_accel_sea_level;
161  if (sea_level_radius > radius) {
162  // If we've told the plane that its sea level radius is unachievable fallback to
163  // straight altitude scaling
164  return radius * eas2tas_sq;
165  } else {
166  // select the requested radius, or the required altitude scale, whichever is safer
167  return MAX(sea_level_radius * eas2tas_sq, radius);
168  }
169  }
170 }
171 
173 {
174  return _WPcircle;
175 }
176 
183 {
184  const float Nu_limit = 0.9f*M_PI;
185  if (fabsf(Nu) > Nu_limit &&
186  fabsf(_last_Nu) > Nu_limit &&
187  labs(wrap_180_cd(_target_bearing_cd - get_yaw_sensor())) > 12000 &&
188  Nu * _last_Nu < 0.0f) {
189  // we are moving away from the target waypoint and pointing
190  // away from the waypoint (not flying backwards). The sign
191  // of Nu has also changed, which means we are
192  // oscillating in our decision about which way to go
193  Nu = _last_Nu;
194  }
195 }
196 
197 // update L1 control for waypoint navigation
198 void AP_L1_Control::update_waypoint(const struct Location &prev_WP, const struct Location &next_WP, float dist_min)
199 {
200 
201  struct Location _current_loc;
202  float Nu;
203  float xtrackVel;
204  float ltrackVel;
205 
206  uint32_t now = AP_HAL::micros();
207  float dt = (now - _last_update_waypoint_us) * 1.0e-6f;
208  if (dt > 0.1) {
209  dt = 0.1;
210  _L1_xtrack_i = 0.0f;
211  }
213 
214  // Calculate L1 gain required for specified damping
215  float K_L1 = 4.0f * _L1_damping * _L1_damping;
216 
217  // Get current position and velocity
218  if (_ahrs.get_position(_current_loc) == false) {
219  // if no GPS loc available, maintain last nav/target_bearing
220  _data_is_stale = true;
221  return;
222  }
223 
224  Vector2f _groundspeed_vector = _ahrs.groundspeed_vector();
225 
226  // update _target_bearing_cd
227  _target_bearing_cd = get_bearing_cd(_current_loc, next_WP);
228 
229  //Calculate groundspeed
230  float groundSpeed = _groundspeed_vector.length();
231  if (groundSpeed < 0.1f) {
232  // use a small ground speed vector in the right direction,
233  // allowing us to use the compass heading at zero GPS velocity
234  groundSpeed = 0.1f;
235  _groundspeed_vector = Vector2f(cosf(get_yaw()), sinf(get_yaw())) * groundSpeed;
236  }
237 
238  // Calculate time varying control parameters
239  // Calculate the L1 length required for specified period
240  // 0.3183099 = 1/1/pipi
241  _L1_dist = MAX(0.3183099f * _L1_damping * _L1_period * groundSpeed, dist_min);
242 
243  // Calculate the NE position of WP B relative to WP A
244  Vector2f AB = location_diff(prev_WP, next_WP);
245  float AB_length = AB.length();
246 
247  // Check for AB zero length and track directly to the destination
248  // if too small
249  if (AB.length() < 1.0e-6f) {
250  AB = location_diff(_current_loc, next_WP);
251  if (AB.length() < 1.0e-6f) {
252  AB = Vector2f(cosf(get_yaw()), sinf(get_yaw()));
253  }
254  }
255  AB.normalize();
256 
257  // Calculate the NE position of the aircraft relative to WP A
258  Vector2f A_air = location_diff(prev_WP, _current_loc);
259 
260  // calculate distance to target track, for reporting
261  _crosstrack_error = A_air % AB;
262 
263  //Determine if the aircraft is behind a +-135 degree degree arc centred on WP A
264  //and further than L1 distance from WP A. Then use WP A as the L1 reference point
265  //Otherwise do normal L1 guidance
266  float WP_A_dist = A_air.length();
267  float alongTrackDist = A_air * AB;
268  if (WP_A_dist > _L1_dist && alongTrackDist/MAX(WP_A_dist, 1.0f) < -0.7071f)
269  {
270  //Calc Nu to fly To WP A
271  Vector2f A_air_unit = (A_air).normalized(); // Unit vector from WP A to aircraft
272  xtrackVel = _groundspeed_vector % (-A_air_unit); // Velocity across line
273  ltrackVel = _groundspeed_vector * (-A_air_unit); // Velocity along line
274  Nu = atan2f(xtrackVel,ltrackVel);
275  _nav_bearing = atan2f(-A_air_unit.y , -A_air_unit.x); // bearing (radians) from AC to L1 point
276  } else if (alongTrackDist > AB_length + groundSpeed*3) {
277  // we have passed point B by 3 seconds. Head towards B
278  // Calc Nu to fly To WP B
279  Vector2f B_air = location_diff(next_WP, _current_loc);
280  Vector2f B_air_unit = (B_air).normalized(); // Unit vector from WP B to aircraft
281  xtrackVel = _groundspeed_vector % (-B_air_unit); // Velocity across line
282  ltrackVel = _groundspeed_vector * (-B_air_unit); // Velocity along line
283  Nu = atan2f(xtrackVel,ltrackVel);
284  _nav_bearing = atan2f(-B_air_unit.y , -B_air_unit.x); // bearing (radians) from AC to L1 point
285  } else { //Calc Nu to fly along AB line
286 
287  //Calculate Nu2 angle (angle of velocity vector relative to line connecting waypoints)
288  xtrackVel = _groundspeed_vector % AB; // Velocity cross track
289  ltrackVel = _groundspeed_vector * AB; // Velocity along track
290  float Nu2 = atan2f(xtrackVel,ltrackVel);
291  //Calculate Nu1 angle (Angle to L1 reference point)
292  float sine_Nu1 = _crosstrack_error/MAX(_L1_dist, 0.1f);
293  //Limit sine of Nu1 to provide a controlled track capture angle of 45 deg
294  sine_Nu1 = constrain_float(sine_Nu1, -0.7071f, 0.7071f);
295  float Nu1 = asinf(sine_Nu1);
296 
297  // compute integral error component to converge to a crosstrack of zero when traveling
298  // straight but reset it when disabled or if it changes. That allows for much easier
299  // tuning by having it re-converge each time it changes.
301  _L1_xtrack_i = 0;
303  } else if (fabsf(Nu1) < radians(5)) {
304  _L1_xtrack_i += Nu1 * _L1_xtrack_i_gain * dt;
305 
306  // an AHRS_TRIM_X=0.1 will drift to about 0.08 so 0.1 is a good worst-case to clip at
308  }
309 
310  // to converge to zero we must push Nu1 harder
311  Nu1 += _L1_xtrack_i;
312 
313  Nu = Nu1 + Nu2;
314  _nav_bearing = atan2f(AB.y, AB.x) + Nu1; // bearing (radians) from AC to L1 point
315  }
316 
318  _last_Nu = Nu;
319 
320  //Limit Nu to +-(pi/2)
321  Nu = constrain_float(Nu, -1.5708f, +1.5708f);
322  _latAccDem = K_L1 * groundSpeed * groundSpeed / _L1_dist * sinf(Nu);
323 
324  // Waypoint capture status is always false during waypoint following
325  _WPcircle = false;
326 
327  _bearing_error = Nu; // bearing error angle (radians), +ve to left of track
328 
329  _data_is_stale = false; // status are correctly updated with current waypoint data
330 }
331 
332 // update L1 control for loitering
333 void AP_L1_Control::update_loiter(const struct Location &center_WP, float radius, int8_t loiter_direction)
334 {
335  struct Location _current_loc;
336 
337  // scale loiter radius with square of EAS2TAS to allow us to stay
338  // stable at high altitude
339  radius = loiter_radius(radius);
340 
341  // Calculate guidance gains used by PD loop (used during circle tracking)
342  float omega = (6.2832f / _L1_period);
343  float Kx = omega * omega;
344  float Kv = 2.0f * _L1_damping * omega;
345 
346  // Calculate L1 gain required for specified damping (used during waypoint capture)
347  float K_L1 = 4.0f * _L1_damping * _L1_damping;
348 
349  //Get current position and velocity
350  if (_ahrs.get_position(_current_loc) == false) {
351  // if no GPS loc available, maintain last nav/target_bearing
352  _data_is_stale = true;
353  return;
354  }
355 
356  Vector2f _groundspeed_vector = _ahrs.groundspeed_vector();
357 
358  //Calculate groundspeed
359  float groundSpeed = MAX(_groundspeed_vector.length() , 1.0f);
360 
361 
362  // update _target_bearing_cd
363  _target_bearing_cd = get_bearing_cd(_current_loc, center_WP);
364 
365 
366  // Calculate time varying control parameters
367  // Calculate the L1 length required for specified period
368  // 0.3183099 = 1/pi
369  _L1_dist = 0.3183099f * _L1_damping * _L1_period * groundSpeed;
370 
371  //Calculate the NE position of the aircraft relative to WP A
372  Vector2f A_air = location_diff(center_WP, _current_loc);
373 
374  // Calculate the unit vector from WP A to aircraft
375  // protect against being on the waypoint and having zero velocity
376  // if too close to the waypoint, use the velocity vector
377  // if the velocity vector is too small, use the heading vector
378  Vector2f A_air_unit;
379  if (A_air.length() > 0.1f) {
380  A_air_unit = A_air.normalized();
381  } else {
382  if (_groundspeed_vector.length() < 0.1f) {
383  A_air_unit = Vector2f(cosf(_ahrs.yaw), sinf(_ahrs.yaw));
384  } else {
385  A_air_unit = _groundspeed_vector.normalized();
386  }
387  }
388 
389  //Calculate Nu to capture center_WP
390  float xtrackVelCap = A_air_unit % _groundspeed_vector; // Velocity across line - perpendicular to radial inbound to WP
391  float ltrackVelCap = - (_groundspeed_vector * A_air_unit); // Velocity along line - radial inbound to WP
392  float Nu = atan2f(xtrackVelCap,ltrackVelCap);
393 
395  _last_Nu = Nu;
396 
397  Nu = constrain_float(Nu, -M_PI_2, M_PI_2); //Limit Nu to +- Pi/2
398 
399  //Calculate lat accln demand to capture center_WP (use L1 guidance law)
400  float latAccDemCap = K_L1 * groundSpeed * groundSpeed / _L1_dist * sinf(Nu);
401 
402  //Calculate radial position and velocity errors
403  float xtrackVelCirc = -ltrackVelCap; // Radial outbound velocity - reuse previous radial inbound velocity
404  float xtrackErrCirc = A_air.length() - radius; // Radial distance from the loiter circle
405 
406  // keep crosstrack error for reporting
407  _crosstrack_error = xtrackErrCirc;
408 
409  //Calculate PD control correction to circle waypoint_ahrs.roll
410  float latAccDemCircPD = (xtrackErrCirc * Kx + xtrackVelCirc * Kv);
411 
412  //Calculate tangential velocity
413  float velTangent = xtrackVelCap * float(loiter_direction);
414 
415  //Prevent PD demand from turning the wrong way by limiting the command when flying the wrong way
416  if (ltrackVelCap < 0.0f && velTangent < 0.0f) {
417  latAccDemCircPD = MAX(latAccDemCircPD, 0.0f);
418  }
419 
420  // Calculate centripetal acceleration demand
421  float latAccDemCircCtr = velTangent * velTangent / MAX((0.5f * radius), (radius + xtrackErrCirc));
422 
423  //Sum PD control and centripetal acceleration to calculate lateral manoeuvre demand
424  float latAccDemCirc = loiter_direction * (latAccDemCircPD + latAccDemCircCtr);
425 
426  // Perform switchover between 'capture' and 'circle' modes at the
427  // point where the commands cross over to achieve a seamless transfer
428  // Only fly 'capture' mode if outside the circle
429  if (xtrackErrCirc > 0.0f && loiter_direction * latAccDemCap < loiter_direction * latAccDemCirc) {
430  _latAccDem = latAccDemCap;
431  _WPcircle = false;
432  _bearing_error = Nu; // angle between demanded and achieved velocity vector, +ve to left of track
433  _nav_bearing = atan2f(-A_air_unit.y , -A_air_unit.x); // bearing (radians) from AC to L1 point
434  } else {
435  _latAccDem = latAccDemCirc;
436  _WPcircle = true;
437  _bearing_error = 0.0f; // bearing error (radians), +ve to left of track
438  _nav_bearing = atan2f(-A_air_unit.y , -A_air_unit.x); // bearing (radians)from AC to L1 point
439  }
440 
441  _data_is_stale = false; // status are correctly updated with current waypoint data
442 }
443 
444 
445 // update L1 control for heading hold navigation
446 void AP_L1_Control::update_heading_hold(int32_t navigation_heading_cd)
447 {
448  // Calculate normalised frequency for tracking loop
449  const float omegaA = 4.4428f/_L1_period; // sqrt(2)*pi/period
450  // Calculate additional damping gain
451 
452  int32_t Nu_cd;
453  float Nu;
454 
455  // copy to _target_bearing_cd and _nav_bearing
456  _target_bearing_cd = wrap_180_cd(navigation_heading_cd);
457  _nav_bearing = radians(navigation_heading_cd * 0.01f);
458 
460  Nu_cd = wrap_180_cd(Nu_cd);
461  Nu = radians(Nu_cd * 0.01f);
462 
463  Vector2f _groundspeed_vector = _ahrs.groundspeed_vector();
464 
465  //Calculate groundspeed
466  float groundSpeed = _groundspeed_vector.length();
467 
468  // Calculate time varying control parameters
469  _L1_dist = groundSpeed / omegaA; // L1 distance is adjusted to maintain a constant tracking loop frequency
470  float VomegaA = groundSpeed * omegaA;
471 
472  // Waypoint capture status is always false during heading hold
473  _WPcircle = false;
474 
475  _crosstrack_error = 0;
476 
477  _bearing_error = Nu; // bearing error angle (radians), +ve to left of track
478 
479  // Limit Nu to +-pi
480  Nu = constrain_float(Nu, -M_PI_2, M_PI_2);
481  _latAccDem = 2.0f*sinf(Nu)*VomegaA;
482 
483  _data_is_stale = false; // status are correctly updated with current waypoint data
484 }
485 
486 // update L1 control for level flight on current heading
488 {
489  // copy to _target_bearing_cd and _nav_bearing
492  _bearing_error = 0;
493  _crosstrack_error = 0;
494 
495  // Waypoint capture status is always false during heading hold
496  _WPcircle = false;
497 
498  _latAccDem = 0;
499 
500  _data_is_stale = false; // status are correctly updated with current waypoint data
501 }
void update_heading_hold(int32_t navigation_heading_cd)
Vector2< float > Vector2f
Definition: vector2.h:239
uint32_t _last_update_waypoint_us
#define M_PI_2
Definition: definitions.h:15
float get_yaw_sensor()
AP_AHRS & _ahrs
Definition: AP_L1_Control.h:80
virtual bool get_position(struct Location &loc) const =0
float _nav_bearing
Definition: AP_L1_Control.h:96
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
void update_level_flight(void)
float pitch
Definition: AP_AHRS.h:225
int32_t nav_bearing_cd(void) const
float yaw
Definition: AP_AHRS.h:226
auto wrap_180_cd(const T angle) -> decltype(wrap_180(angle, 100.f))
Definition: AP_Math.cpp:111
int32_t bearing_error_cd(void) const
AP_Float _L1_xtrack_i_gain
AP_Float _L1_period
virtual Vector2f groundspeed_vector(void)
Definition: AP_AHRS.cpp:235
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
#define MIN(a, b)
Definition: usb_conf.h:215
int32_t get_bearing_cd(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:56
float turn_distance(float wp_radius) const
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
#define RadiansToCentiDegrees(x)
Definition: definitions.h:44
float _bearing_error
Definition: AP_L1_Control.h:99
T y
Definition: vector2.h:37
Vector2< T > normalized() const
Definition: vector2.h:146
const AP_SpdHgtControl * _spdHgtControl
Definition: AP_L1_Control.h:83
int32_t nav_roll_cd(void) const
AP_Float _L1_damping
Vector2f location_diff(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:139
float wrap_PI(const T radian)
Definition: AP_Math.cpp:152
#define GRAVITY_MSS
Definition: definitions.h:47
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
void update_loiter(const struct Location &center_WP, float radius, int8_t loiter_direction)
int32_t target_bearing_cd(void) const
#define AP_GROUPINFO_FRAME(name, idx, clazz, element, def, frame_flags)
Definition: AP_Param.h:96
float _crosstrack_error
bool reached_loiter_target(void)
float length(void) const
Definition: vector2.cpp:24
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
T x
Definition: vector2.h:37
int32_t _target_bearing_cd
float lateral_acceleration(void) const
std::enable_if< std::is_integral< typename std::common_type< Arithmetic1, Arithmetic2 >::type >::value,bool >::type is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2)
Definition: AP_Math.cpp:12
static constexpr float radians(float deg)
Definition: AP_Math.h:158
void normalize()
Definition: vector2.h:140
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_L1_Control.h:72
#define AP_PARAM_FRAME_PLANE
Definition: AP_Param.h:79
L1 Control algorithm. This is a instance of an AP_Navigation class.
AP_Float _loiter_bank_limit
void _prevent_indecision(float &Nu)
float sq(const T val)
Definition: AP_Math.h:170
float loiter_radius(const float loiter_radius) const
virtual float get_target_airspeed(void) const =0
float get_EAS2TAS(void) const
Definition: AP_AHRS.h:290
void update_waypoint(const struct Location &prev_WP, const struct Location &next_WP, float dist_min=0.0f)
#define degrees(x)
Definition: moduletest.c:23
#define M_PI
Definition: definitions.h:10
float _L1_xtrack_i_gain_prev
int32_t yaw_sensor
Definition: AP_AHRS.h:231
uint32_t micros()
Definition: system.cpp:152
#define AP_GROUPEND
Definition: AP_Param.h:121