APM:Libraries
AR_AttitudeControl.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 #include <AP_Math/AP_Math.h>
17 #include <AP_HAL/AP_HAL.h>
18 #include "AR_AttitudeControl.h"
19 
20 extern const AP_HAL::HAL& hal;
21 
23 
24  // @Param: _STR_RAT_P
25  // @DisplayName: Steering control rate P gain
26  // @Description: Steering control rate P gain. Converts the turn rate error (in radians/sec) to a steering control output (in the range -1 to +1)
27  // @Range: 0.000 2.000
28  // @Increment: 0.01
29  // @User: Standard
30 
31  // @Param: _STR_RAT_I
32  // @DisplayName: Steering control I gain
33  // @Description: Steering control I gain. Corrects long term error between the desired turn rate (in rad/s) and actual
34  // @Range: 0.000 2.000
35  // @Increment: 0.01
36  // @User: Standard
37 
38  // @Param: _STR_RAT_IMAX
39  // @DisplayName: Steering control I gain maximum
40  // @Description: Steering control I gain maximum. Constraings the steering output (range -1 to +1) that the I term will generate
41  // @Range: 0.000 1.000
42  // @Increment: 0.01
43  // @User: Standard
44 
45  // @Param: _STR_RAT_D
46  // @DisplayName: Steering control D gain
47  // @Description: Steering control D gain. Compensates for short-term change in desired turn rate vs actual
48  // @Range: 0.000 0.400
49  // @Increment: 0.001
50  // @User: Standard
51 
52  // @Param: _STR_RAT_FF
53  // @DisplayName: Steering control feed forward
54  // @Description: Steering control feed forward
55  // @Range: 0.000 3.000
56  // @Increment: 0.001
57  // @User: Standard
58 
59  // @Param: _STR_RAT_FILT
60  // @DisplayName: Steering control filter frequency
61  // @Description: Steering control input filter. Lower values reduce noise but add delay.
62  // @Range: 0.000 100.000
63  // @Increment: 0.1
64  // @Units: Hz
65  // @User: Standard
66  AP_SUBGROUPINFO(_steer_rate_pid, "_STR_RAT_", 1, AR_AttitudeControl, AC_PID),
67 
68  // @Param: _SPEED_P
69  // @DisplayName: Speed control P gain
70  // @Description: Speed control P gain. Converts the error between the desired speed (in m/s) and actual speed to a motor output (in the range -1 to +1)
71  // @Range: 0.010 2.000
72  // @Increment: 0.01
73  // @User: Standard
74 
75  // @Param: _SPEED_I
76  // @DisplayName: Speed control I gain
77  // @Description: Speed control I gain. Corrects long term error between the desired speed (in m/s) and actual speed
78  // @Range: 0.000 2.000
79  // @User: Standard
80 
81  // @Param: _SPEED_IMAX
82  // @DisplayName: Speed control I gain maximum
83  // @Description: Speed control I gain maximum. Constraings the maximum motor output (range -1 to +1) that the I term will generate
84  // @Range: 0.000 1.000
85  // @Increment: 0.01
86  // @User: Standard
87 
88  // @Param: _SPEED_D
89  // @DisplayName: Speed control D gain
90  // @Description: Speed control D gain. Compensates for short-term change in desired speed vs actual
91  // @Range: 0.000 0.400
92  // @Increment: 0.001
93  // @User: Standard
94 
95  // @Param: _SPEED_FF
96  // @DisplayName: Speed control feed forward
97  // @Description: Speed control feed forward
98  // @Range: 0.000 0.500
99  // @Increment: 0.001
100  // @User: Standard
101 
102  // @Param: _SPEED_FILT
103  // @DisplayName: Speed control filter frequency
104  // @Description: Speed control input filter. Lower values reduce noise but add delay.
105  // @Range: 0.000 100.000
106  // @Increment: 0.1
107  // @Units: Hz
108  // @User: Standard
109  AP_SUBGROUPINFO(_throttle_speed_pid, "_SPEED_", 2, AR_AttitudeControl, AC_PID),
110 
111  // @Param: _ACCEL_MAX
112  // @DisplayName: Speed control acceleration (and deceleration) maximum in m/s/s
113  // @Description: Speed control acceleration (and deceleration) maximum in m/s/s. 0 to disable acceleration limiting
114  // @Range: 0.0 10.0
115  // @Increment: 0.1
116  // @Units: m/s/s
117  // @User: Standard
118  AP_GROUPINFO("_ACCEL_MAX", 3, AR_AttitudeControl, _throttle_accel_max, AR_ATTCONTROL_THR_ACCEL_MAX),
119 
120  // @Param: _BRAKE
121  // @DisplayName: Speed control brake enable/disable
122  // @Description: Speed control brake enable/disable. Allows sending a reversed output to the motors to slow the vehicle.
123  // @Values: 0:Disable,1:Enable
124  // @User: Standard
125  AP_GROUPINFO("_BRAKE", 4, AR_AttitudeControl, _brake_enable, 0),
126 
127  // @Param: _STOP_SPEED
128  // @DisplayName: Speed control stop speed
129  // @Description: Speed control stop speed. Motor outputs to zero once vehicle speed falls below this value
130  // @Range: 0.00 0.50
131  // @Increment: 0.01
132  // @Units: m/s
133  // @User: Standard
134  AP_GROUPINFO("_STOP_SPEED", 5, AR_AttitudeControl, _stop_speed, AR_ATTCONTROL_STOP_SPEED_DEFAULT),
135 
136  // @Param: _STR_ANG_P
137  // @DisplayName: Steering control angle P gain
138  // @Description: Steering control angle P gain. Converts the error between the desired heading/yaw (in radians) and actual heading/yaw to a desired turn rate (in rad/sec)
139  // @Range: 1.000 10.000
140  // @Increment: 0.1
141  // @User: Standard
142  AP_SUBGROUPINFO(_steer_angle_p, "_STR_ANG_", 6, AR_AttitudeControl, AC_P),
143 
144  // @Param: _STR_ACC_MAX
145  // @DisplayName: Steering control angular acceleration maximum
146  // @Description: Steering control angular acceleartion maximum (in deg/s/s). 0 to disable acceleration limiting
147  // @Range: 0 1000
148  // @Increment: 0.1
149  // @Units: deg/s/s
150  // @User: Standard
151  AP_GROUPINFO("_STR_ACC_MAX", 7, AR_AttitudeControl, _steer_accel_max, AR_ATTCONTROL_STEER_ACCEL_MAX),
152 
153  // @Param: _STR_RAT_MAX
154  // @DisplayName: Steering control rotation rate maximum
155  // @Description: Steering control rotation rate maximum in deg/s. 0 to remove rate limiting
156  // @Range: 0 1000
157  // @Increment: 0.1
158  // @Units: deg/s
159  // @User: Standard
160  AP_GROUPINFO("_STR_RAT_MAX", 8, AR_AttitudeControl, _steer_rate_max, AR_ATTCONTROL_STEER_RATE_MAX),
161 
162  // @Param: _DECEL_MAX
163  // @DisplayName: Speed control deceleration maximum in m/s/s
164  // @Description: Speed control and deceleration maximum in m/s/s. 0 to disable deceleration limiting
165  // @Range: 0.0 10.0
166  // @Increment: 0.1
167  // @Units: m/s/s
168  // @User: Standard
169  AP_GROUPINFO("_DECEL_MAX", 9, AR_AttitudeControl, _throttle_decel_max, 0.00f),
170 
172 };
173 
175  _ahrs(ahrs),
176  _steer_angle_p(AR_ATTCONTROL_STEER_ANG_P),
179 {
181 }
182 
183 // return a steering servo output from -1.0 to +1.0 given a desired lateral acceleration rate in m/s/s.
184 // positive lateral acceleration is to the right.
185 float AR_AttitudeControl::get_steering_out_lat_accel(float desired_accel, bool motor_limit_left, bool motor_limit_right, float dt)
186 {
187  // record desired accel for reporting purposes
189  _desired_lat_accel = desired_accel;
190 
191  // get speed forward
192  float speed;
193  if (!get_forward_speed(speed)) {
194  // we expect caller will not try to control heading using rate control without a valid speed estimate
195  // on failure to get speed we do not attempt to steer
196  return 0.0f;
197  }
198 
199  // enforce minimum speed to stop oscillations when first starting to move
200  if (fabsf(speed) < AR_ATTCONTROL_STEER_SPEED_MIN) {
201  if (is_negative(speed)) {
203  } else {
205  }
206  }
207 
208  // Calculate the desired steering rate given desired_accel and speed
209  const float desired_rate = desired_accel / speed;
210 
211  return get_steering_out_rate(desired_rate, motor_limit_left, motor_limit_right, dt);
212 }
213 
214 // return a steering servo output from -1 to +1 given a heading in radians
215 float AR_AttitudeControl::get_steering_out_heading(float heading_rad, float rate_max, bool motor_limit_left, bool motor_limit_right, float dt)
216 {
217  // calculate heading error (in radians)
218  const float yaw_error = wrap_PI(heading_rad - _ahrs.yaw);
219 
220  // Calculate the desired turn rate (in radians) from the angle error (also in radians)
221  float desired_rate = _steer_angle_p.get_p(yaw_error);
222  // limit desired_rate if a custom pivot turn rate is selected, otherwise use ATC_STR_RAT_MAX
223  if (is_positive(rate_max)) {
224  desired_rate = constrain_float(desired_rate, -rate_max, rate_max);
225  }
226 
227  return get_steering_out_rate(desired_rate, motor_limit_left, motor_limit_right, dt);
228 }
229 
230 // return a steering servo output from -1 to +1 given a
231 // desired yaw rate in radians/sec. Positive yaw is to the right.
232 float AR_AttitudeControl::get_steering_out_rate(float desired_rate, bool motor_limit_left, bool motor_limit_right, float dt)
233 {
234  // sanity check dt
235  dt = constrain_float(dt, 0.0f, 1.0f);
236 
237  // if not called recently, reset input filter and desired turn rate to actual turn rate (used for accel limiting)
238  const uint32_t now = AP_HAL::millis();
242  }
243  _steer_turn_last_ms = now;
244 
245  // acceleration limit desired turn rate
247  const float change_max = radians(_steer_accel_max) * dt;
248  desired_rate = constrain_float(desired_rate, _desired_turn_rate - change_max, _desired_turn_rate + change_max);
249  }
250  _desired_turn_rate = desired_rate;
251 
252  // rate limit desired turn rate
254  const float steer_rate_max_rad = radians(_steer_rate_max);
255  _desired_turn_rate = constrain_float(_desired_turn_rate, -steer_rate_max_rad, steer_rate_max_rad);
256  }
257 
258  // Calculate the steering rate error (rad/sec)
259  // We do this in earth frame to allow for rover leaning over in hard corners
260  const float rate_error = (_desired_turn_rate - _ahrs.get_yaw_rate_earth());
261 
262  // set PID's dt
264 
265  // record desired rate for logging purposes only
267 
268  // pass error to PID controller
270 
271  // get feed-forward
272  const float ff = _steer_rate_pid.get_ff(_desired_turn_rate);
273 
274  // get p
275  const float p = _steer_rate_pid.get_p();
276 
277  // get i unless non-skid-steering rover at low speed or steering output has hit a limit
278  float i = _steer_rate_pid.get_integrator();
279  if ((is_negative(rate_error) && !motor_limit_left) || (is_positive(rate_error) && !motor_limit_right)) {
280  i = _steer_rate_pid.get_i();
281  }
282 
283  // get d
284  const float d = _steer_rate_pid.get_d();
285 
286  // constrain and return final output
287  return constrain_float(ff + p + i + d, -1.0f, 1.0f);
288 }
289 
290 // get latest desired turn rate in rad/sec (recorded during calls to get_steering_out_rate)
292 {
293  // return zero if no recent calls to turn rate controller
295  return 0.0f;
296  }
297  return _desired_turn_rate;
298 }
299 
300 // get latest desired lateral acceleration in m/s/s (recorded during calls to get_steering_out_lat_accel)
302 {
303  // return zero if no recent calls to lateral acceleration controller
305  return 0.0f;
306  }
307  return _desired_lat_accel;
308 }
309 
310 // get actual lateral acceleration in m/s/s. returns true on success
311 bool AR_AttitudeControl::get_lat_accel(float &lat_accel) const
312 {
313  float speed;
314  if (!get_forward_speed(speed)) {
315  return false;
316  }
317  lat_accel = speed * _ahrs.get_yaw_rate_earth();
318  return true;
319 }
320 
321 // return a throttle output from -1 to +1 given a desired speed in m/s (use negative speeds to travel backwards)
322 // motor_limit should be true if motors have hit their upper or lower limits
323 // cruise speed should be in m/s, cruise throttle should be a number from -1 to +1
324 float AR_AttitudeControl::get_throttle_out_speed(float desired_speed, bool motor_limit_low, bool motor_limit_high, float cruise_speed, float cruise_throttle, float dt)
325 {
326  // sanity check dt
327  dt = constrain_float(dt, 0.0f, 1.0f);
328 
329  // get speed forward
330  float speed;
331  if (!get_forward_speed(speed)) {
332  // we expect caller will not try to control heading using rate control without a valid speed estimate
333  // on failure to get speed we do not attempt to steer
334  return 0.0f;
335  }
336 
337  // if not called recently, reset input filter and desired speed to actual speed (used for accel limiting)
338  const uint32_t now = AP_HAL::millis();
339  if (!speed_control_active()) {
341  _desired_speed = speed;
342  }
343  _speed_last_ms = now;
344 
345  // acceleration limit desired speed
346  _desired_speed = get_desired_speed_accel_limited(desired_speed, dt);
347 
348  // set PID's dt
350 
351  // calculate speed error and pass to PID controller
352  const float speed_error = desired_speed - speed;
354 
355  // record desired speed for logging purposes only
356  _throttle_speed_pid.set_desired_rate(desired_speed);
357 
358  // get feed-forward
359  const float ff = _throttle_speed_pid.get_ff(desired_speed);
360 
361  // get p
362  const float p = _throttle_speed_pid.get_p();
363 
364  // get i unless moving at low speed or motors have hit a limit
366  if ((is_negative(speed_error) && !motor_limit_low && !_throttle_limit_low) || (is_positive(speed_error) && !motor_limit_high && !_throttle_limit_high)) {
368  }
369 
370  // get d
371  const float d = _throttle_speed_pid.get_d();
372 
373  // calculate base throttle (protect against divide by zero)
374  float throttle_base = 0.0f;
375  if (is_positive(cruise_speed) && is_positive(cruise_throttle)) {
376  throttle_base = desired_speed * (cruise_throttle / cruise_speed);
377  }
378 
379  // calculate final output
380  float throttle_out = (ff+p+i+d+throttle_base);
381 
382  // clear local limit flags used to stop i-term build-up as we stop reversed outputs going to motors
383  _throttle_limit_low = false;
384  _throttle_limit_high = false;
385 
386  // protect against reverse output being sent to the motors unless braking has been enabled
387  if (!_brake_enable) {
388  // if both desired speed and actual speed are positive, do not allow negative values
389  if ((desired_speed >= 0.0f) && (throttle_out <= 0.0f)) {
390  throttle_out = 0.0f;
391  _throttle_limit_low = true;
392  }
393  if ((desired_speed <= 0.0f) && (throttle_out >= 0.0f)) {
394  throttle_out = 0.0f;
395  _throttle_limit_high = true;
396  }
397  }
398 
399  // final output throttle in range -1 to 1
400  return throttle_out;
401 }
402 
403 // return a throttle output from -1 to +1 to perform a controlled stop. returns true once the vehicle has stopped
404 float AR_AttitudeControl::get_throttle_out_stop(bool motor_limit_low, bool motor_limit_high, float cruise_speed, float cruise_throttle, float dt, bool &stopped)
405 {
406  // get current system time
407  const uint32_t now = AP_HAL::millis();
408 
409  // if we were stopped in the last 300ms, assume we are still stopped
410  bool _stopped = (_stop_last_ms != 0) && (now - _stop_last_ms) < 300;
411 
412  // get deceleration limited speed
413  float desired_speed_limited = get_desired_speed_accel_limited(0.0f, dt);
414 
415  // get speed forward
416  float speed;
417  if (!get_forward_speed(speed)) {
418  // could not get speed so assume stopped
419  _stopped = true;
420  } else {
421  // if desired speed is zero and vehicle drops below _stop_speed consider it stopped
422  if (is_zero(desired_speed_limited) && fabsf(speed) <= fabsf(_stop_speed)) {
423  _stopped = true;
424  }
425  }
426 
427  // set stopped status for caller
428  stopped = _stopped;
429 
430  // if stopped return zero
431  if (stopped) {
432  // update last time we thought we were stopped
433  _stop_last_ms = now;
434  return 0.0f;
435  } else {
436  // clear stopped system time
437  _stop_last_ms = 0;
438  // run speed controller to bring vehicle to stop
439  return get_throttle_out_speed(desired_speed_limited, motor_limit_low, motor_limit_high, cruise_speed, cruise_throttle, dt);
440  }
441 }
442 
443 // get forward speed in m/s (earth-frame horizontal velocity but only along vehicle x-axis). returns true on success
445 {
446  Vector3f velocity;
447  if (!_ahrs.get_velocity_NED(velocity)) {
448  // use less accurate GPS, assuming entire length is along forward/back axis of vehicle
449  if (AP::gps().status() >= AP_GPS::GPS_OK_FIX_3D) {
450  if (labs(wrap_180_cd(_ahrs.yaw_sensor - AP::gps().ground_course_cd())) <= 9000) {
451  speed = AP::gps().ground_speed();
452  } else {
453  speed = -AP::gps().ground_speed();
454  }
455  return true;
456  } else {
457  return false;
458  }
459  }
460  // calculate forward speed velocity into body frame
461  speed = velocity.x*_ahrs.cos_yaw() + velocity.y*_ahrs.sin_yaw();
462  return true;
463 }
464 
466 {
468  return _throttle_decel_max;
469  } else {
470  return _throttle_accel_max;
471  }
472 }
473 
474 // check if speed controller active
476 {
477  // active if there have been recent calls to speed controller
479  return false;
480  }
481  return true;
482 }
483 
484 // get latest desired speed recorded during call to get_throttle_out_speed. For reporting purposes only
486 {
487  // return zero if no recent calls to speed controller
488  if (!speed_control_active()) {
489  return 0.0f;
490  }
491  return _desired_speed;
492 }
493 
494 // get acceleration limited desired speed
495 float AR_AttitudeControl::get_desired_speed_accel_limited(float desired_speed, float dt) const
496 {
497  // sanity check dt
498  dt = constrain_float(dt, 0.0f, 1.0f);
499 
500  // use previous desired speed as basis for accel limiting
501  float speed_prev = _desired_speed;
502 
503  // if no recent calls to speed controller limit based on current speed
504  if (!speed_control_active()) {
505  get_forward_speed(speed_prev);
506  }
507 
508  // acceleration limit desired speed
509  float speed_change_max;
510  if (fabsf(desired_speed) < fabsf(_desired_speed) && is_positive(_throttle_decel_max)) {
511  speed_change_max = _throttle_decel_max * dt;
512  } else {
513  speed_change_max = _throttle_accel_max * dt;
514  }
515  return constrain_float(desired_speed, speed_prev - speed_change_max, speed_prev + speed_change_max);
516 }
517 
518 // get minimum stopping distance (in meters) given a speed (in m/s)
520 {
521  // get maximum vehicle deceleration
522  const float accel_max = get_accel_max();
523 
524  // avoid divide by zero
525  if ((accel_max <= 0.0f) || is_zero(speed)) {
526  return 0.0f;
527  }
528 
529  // assume linear deceleration
530  return 0.5f * sq(speed) / accel_max;
531 }
const AP_AHRS & _ahrs
float get_steering_out_lat_accel(float desired_accel, bool motor_limit_left, bool motor_limit_right, float dt)
float cos_yaw() const
Definition: AP_AHRS.h:402
virtual bool get_velocity_NED(Vector3f &vec) const
Definition: AP_AHRS.h:309
#define AR_ATTCONTROL_THR_ACCEL_MAX
bool speed_control_active() const
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
float sin_yaw() const
Definition: AP_AHRS.h:411
float get_desired_turn_rate() const
#define AR_ATTCONTROL_THR_SPEED_IMAX
#define AR_ATTCONTROL_THR_SPEED_D
float get_throttle_out_stop(bool motor_limit_low, bool motor_limit_high, float cruise_speed, float cruise_throttle, float dt, bool &stopped)
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
float get_d()
Definition: AC_PID.cpp:155
#define AR_ATTCONTROL_STEER_RATE_D
AR_AttitudeControl(AP_AHRS &ahrs)
float yaw
Definition: AP_AHRS.h:226
float get_yaw_rate_earth(void) const
Definition: AP_AHRS.h:206
bool is_positive(const T fVal1)
Definition: AP_Math.h:50
auto wrap_180_cd(const T angle) -> decltype(wrap_180(angle, 100.f))
Definition: AP_Math.cpp:111
float get_stopping_distance(float speed) const
bool get_forward_speed(float &speed) const
float get_steering_out_heading(float heading_rad, float rate_max, bool motor_limit_left, bool motor_limit_right, float dt)
int32_t ground_course_cd(uint8_t instance) const
Definition: AP_GPS.h:252
#define AR_ATTCONTROL_STEER_RATE_FILT
#define AR_ATTCONTROL_DT
#define AR_ATTCONTROL_STEER_RATE_MAX
float get_desired_lat_accel() const
Object managing one P controller.
Definition: AC_P.h:13
#define AR_ATTCONTROL_STEER_RATE_FF
float get_throttle_out_speed(float desired_speed, bool motor_limit_low, bool motor_limit_high, float cruise_speed, float cruise_throttle, float dt)
float wrap_PI(const T radian)
Definition: AP_Math.cpp:152
#define AR_ATTCONTROL_THR_SPEED_I
float ground_speed(uint8_t instance) const
Definition: AP_GPS.h:232
float get_accel_max() const
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
T y
Definition: vector3.h:67
uint32_t millis()
Definition: system.cpp:157
float get_ff(float requested_rate)
Definition: AC_PID.cpp:162
float get_desired_speed() const
#define AR_ATTCONTROL_STEER_ANG_P
#define AR_ATTCONTROL_STEER_RATE_IMAX
#define AR_ATTCONTROL_STEER_SPEED_MIN
GPS_Status status(uint8_t instance) const
Query GPS status.
Definition: AP_GPS.h:189
#define AR_ATTCONTROL_STOP_SPEED_DEFAULT
void set_desired_rate(float desired)
Definition: AC_PID.h:80
void reset_filter()
Definition: AC_PID.h:48
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
#define AR_ATTCONTROL_STEER_ACCEL_MAX
bool get_lat_accel(float &lat_accel) const
static constexpr float radians(float deg)
Definition: AP_Math.h:158
void set_dt(float dt)
Definition: AC_PID.cpp:69
#define AR_ATTCONTROL_TIMEOUT_MS
void set_input_filter_all(float input)
Definition: AC_PID.cpp:87
#define AR_ATTCONTROL_STEER_RATE_P
float get_steering_out_rate(float desired_rate, bool motor_limit_left, bool motor_limit_right, float dt)
bool is_negative(const T fVal1)
Definition: AP_Math.h:61
float sq(const T val)
Definition: AP_Math.h:170
#define AR_ATTCONTROL_THR_SPEED_FILT
AP_GPS & gps()
Definition: AP_GPS.cpp:1550
float get_p(float error) const
Definition: AC_P.cpp:15
Receiving valid messages and 3D lock.
Definition: AP_GPS.h:100
float get_integrator() const
Definition: AC_PID.h:76
float get_i()
Definition: AC_PID.cpp:140
Copter PID control class.
Definition: AC_PID.h:17
#define AP_SUBGROUPINFO(element, name, idx, thisclazz, elclazz)
Definition: AP_Param.h:109
float get_desired_speed_accel_limited(float desired_speed, float dt) const
#define AR_ATTCONTROL_STEER_RATE_I
int32_t yaw_sensor
Definition: AP_AHRS.h:231
static const struct AP_Param::GroupInfo var_info[]
float get_p()
Definition: AC_PID.cpp:134
#define AP_GROUPEND
Definition: AP_Param.h:121
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 AR_ATTCONTROL_THR_SPEED_P
T x
Definition: vector3.h:67
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214