APM:Libraries
AC_PosControl.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 #include "AC_PosControl.h"
3 #include <AP_Math/AP_Math.h>
4 #include <DataFlash/DataFlash.h>
5 
6 extern const AP_HAL::HAL& hal;
7 
8 #if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
9  // default gains for Plane
10  # define POSCONTROL_POS_Z_P 1.0f // vertical position controller P gain default
11  # define POSCONTROL_VEL_Z_P 5.0f // vertical velocity controller P gain default
12  # define POSCONTROL_ACC_Z_P 0.3f // vertical acceleration controller P gain default
13  # define POSCONTROL_ACC_Z_I 1.0f // vertical acceleration controller I gain default
14  # define POSCONTROL_ACC_Z_D 0.0f // vertical acceleration controller D gain default
15  # define POSCONTROL_ACC_Z_IMAX 800 // vertical acceleration controller IMAX gain default
16  # define POSCONTROL_ACC_Z_FILT_HZ 10.0f // vertical acceleration controller input filter default
17  # define POSCONTROL_ACC_Z_DT 0.02f // vertical acceleration controller dt default
18  # define POSCONTROL_POS_XY_P 1.0f // horizontal position controller P gain default
19  # define POSCONTROL_VEL_XY_P 1.4f // horizontal velocity controller P gain default
20  # define POSCONTROL_VEL_XY_I 0.7f // horizontal velocity controller I gain default
21  # define POSCONTROL_VEL_XY_D 0.35f // horizontal velocity controller D gain default
22  # define POSCONTROL_VEL_XY_IMAX 1000.0f // horizontal velocity controller IMAX gain default
23  # define POSCONTROL_VEL_XY_FILT_HZ 5.0f // horizontal velocity controller input filter
24  # define POSCONTROL_VEL_XY_FILT_D_HZ 5.0f // horizontal velocity controller input filter for D
25 #elif APM_BUILD_TYPE(APM_BUILD_ArduSub)
26  // default gains for Sub
27  # define POSCONTROL_POS_Z_P 3.0f // vertical position controller P gain default
28  # define POSCONTROL_VEL_Z_P 8.0f // vertical velocity controller P gain default
29  # define POSCONTROL_ACC_Z_P 0.5f // vertical acceleration controller P gain default
30  # define POSCONTROL_ACC_Z_I 0.1f // vertical acceleration controller I gain default
31  # define POSCONTROL_ACC_Z_D 0.0f // vertical acceleration controller D gain default
32  # define POSCONTROL_ACC_Z_IMAX 100 // vertical acceleration controller IMAX gain default
33  # define POSCONTROL_ACC_Z_FILT_HZ 20.0f // vertical acceleration controller input filter default
34  # define POSCONTROL_ACC_Z_DT 0.0025f // vertical acceleration controller dt default
35  # define POSCONTROL_POS_XY_P 1.0f // horizontal position controller P gain default
36  # define POSCONTROL_VEL_XY_P 1.0f // horizontal velocity controller P gain default
37  # define POSCONTROL_VEL_XY_I 0.5f // horizontal velocity controller I gain default
38  # define POSCONTROL_VEL_XY_D 0.0f // horizontal velocity controller D gain default
39  # define POSCONTROL_VEL_XY_IMAX 1000.0f // horizontal velocity controller IMAX gain default
40  # define POSCONTROL_VEL_XY_FILT_HZ 5.0f // horizontal velocity controller input filter
41  # define POSCONTROL_VEL_XY_FILT_D_HZ 5.0f // horizontal velocity controller input filter for D
42 #else
43  // default gains for Copter / TradHeli
44  # define POSCONTROL_POS_Z_P 1.0f // vertical position controller P gain default
45  # define POSCONTROL_VEL_Z_P 5.0f // vertical velocity controller P gain default
46  # define POSCONTROL_ACC_Z_P 0.5f // vertical acceleration controller P gain default
47  # define POSCONTROL_ACC_Z_I 1.0f // vertical acceleration controller I gain default
48  # define POSCONTROL_ACC_Z_D 0.0f // vertical acceleration controller D gain default
49  # define POSCONTROL_ACC_Z_IMAX 800 // vertical acceleration controller IMAX gain default
50  # define POSCONTROL_ACC_Z_FILT_HZ 20.0f // vertical acceleration controller input filter default
51  # define POSCONTROL_ACC_Z_DT 0.0025f // vertical acceleration controller dt default
52  # define POSCONTROL_POS_XY_P 1.0f // horizontal position controller P gain default
53  # define POSCONTROL_VEL_XY_P 2.0f // horizontal velocity controller P gain default
54  # define POSCONTROL_VEL_XY_I 1.0f // horizontal velocity controller I gain default
55  # define POSCONTROL_VEL_XY_D 0.5f // horizontal velocity controller D gain default
56  # define POSCONTROL_VEL_XY_IMAX 1000.0f // horizontal velocity controller IMAX gain default
57  # define POSCONTROL_VEL_XY_FILT_HZ 5.0f // horizontal velocity controller input filter
58  # define POSCONTROL_VEL_XY_FILT_D_HZ 5.0f // horizontal velocity controller input filter for D
59 #endif
60 
62  // 0 was used for HOVER
63 
64  // @Param: _ACC_XY_FILT
65  // @DisplayName: XY Acceleration filter cutoff frequency
66  // @Description: Lower values will slow the response of the navigation controller and reduce twitchiness
67  // @Units: Hz
68  // @Range: 0.5 5
69  // @Increment: 0.1
70  // @User: Advanced
71  AP_GROUPINFO("_ACC_XY_FILT", 1, AC_PosControl, _accel_xy_filt_hz, POSCONTROL_ACCEL_FILTER_HZ),
72 
73  // @Param: _POSZ_P
74  // @DisplayName: Position (vertical) controller P gain
75  // @Description: Position (vertical) controller P gain. Converts the difference between the desired altitude and actual altitude into a climb or descent rate which is passed to the throttle rate controller
76  // @Range: 1.000 3.000
77  // @User: Standard
78  AP_SUBGROUPINFO(_p_pos_z, "_POSZ_", 2, AC_PosControl, AC_P),
79 
80  // @Param: _VELZ_P
81  // @DisplayName: Velocity (vertical) controller P gain
82  // @Description: Velocity (vertical) controller P gain. Converts the difference between desired vertical speed and actual speed into a desired acceleration that is passed to the throttle acceleration controller
83  // @Range: 1.000 8.000
84  // @User: Standard
85  AP_SUBGROUPINFO(_p_vel_z, "_VELZ_", 3, AC_PosControl, AC_P),
86 
87  // @Param: _ACCZ_P
88  // @DisplayName: Acceleration (vertical) controller P gain
89  // @Description: Acceleration (vertical) controller P gain. Converts the difference between desired vertical acceleration and actual acceleration into a motor output
90  // @Range: 0.500 1.500
91  // @Increment: 0.05
92  // @User: Standard
93 
94  // @Param: _ACCZ_I
95  // @DisplayName: Acceleration (vertical) controller I gain
96  // @Description: Acceleration (vertical) controller I gain. Corrects long-term difference in desired vertical acceleration and actual acceleration
97  // @Range: 0.000 3.000
98  // @User: Standard
99 
100  // @Param: _ACCZ_IMAX
101  // @DisplayName: Acceleration (vertical) controller I gain maximum
102  // @Description: Acceleration (vertical) controller I gain maximum. Constrains the maximum pwm that the I term will generate
103  // @Range: 0 1000
104  // @Units: d%
105  // @User: Standard
106 
107  // @Param: _ACCZ_D
108  // @DisplayName: Acceleration (vertical) controller D gain
109  // @Description: Acceleration (vertical) controller D gain. Compensates for short-term change in desired vertical acceleration vs actual acceleration
110  // @Range: 0.000 0.400
111  // @User: Standard
112 
113  // @Param: _ACCZ_FILT
114  // @DisplayName: Acceleration (vertical) controller filter
115  // @Description: Filter applied to acceleration to reduce noise. Lower values reduce noise but add delay.
116  // @Range: 1.000 100.000
117  // @Units: Hz
118  // @User: Standard
119  AP_SUBGROUPINFO(_pid_accel_z, "_ACCZ_", 4, AC_PosControl, AC_PID),
120 
121  // @Param: _POSXY_P
122  // @DisplayName: Position (horizonal) controller P gain
123  // @Description: Position controller P gain. Converts the distance (in the latitude direction) to the target location into a desired speed which is then passed to the loiter latitude rate controller
124  // @Range: 0.500 2.000
125  // @User: Standard
126  AP_SUBGROUPINFO(_p_pos_xy, "_POSXY_", 5, AC_PosControl, AC_P),
127 
128  // @Param: _VELXY_P
129  // @DisplayName: Velocity (horizontal) P gain
130  // @Description: Velocity (horizontal) P gain. Converts the difference between desired velocity to a target acceleration
131  // @Range: 0.1 6.0
132  // @Increment: 0.1
133  // @User: Advanced
134 
135  // @Param: _VELXY_I
136  // @DisplayName: Velocity (horizontal) I gain
137  // @Description: Velocity (horizontal) I gain. Corrects long-term difference in desired velocity to a target acceleration
138  // @Range: 0.02 1.00
139  // @Increment: 0.01
140  // @User: Advanced
141 
142  // @Param: _VELXY_D
143  // @DisplayName: Velocity (horizontal) D gain
144  // @Description: Velocity (horizontal) D gain. Corrects short-term changes in velocity
145  // @Range: 0.00 1.00
146  // @Increment: 0.001
147  // @User: Advanced
148 
149  // @Param: _VELXY_IMAX
150  // @DisplayName: Velocity (horizontal) integrator maximum
151  // @Description: Velocity (horizontal) integrator maximum. Constrains the target acceleration that the I gain will output
152  // @Range: 0 4500
153  // @Increment: 10
154  // @Units: cm/s/s
155  // @User: Advanced
156 
157  // @Param: _VELXY_FILT
158  // @DisplayName: Velocity (horizontal) input filter
159  // @Description: Velocity (horizontal) input filter. This filter (in hz) is applied to the input for P and I terms
160  // @Range: 0 100
161  // @Units: Hz
162  // @User: Advanced
163 
164  // @Param: _VELXY_D_FILT
165  // @DisplayName: Velocity (horizontal) input filter
166  // @Description: Velocity (horizontal) input filter. This filter (in hz) is applied to the input for P and I terms
167  // @Range: 0 100
168  // @Units: Hz
169  // @User: Advanced
170  AP_SUBGROUPINFO(_pid_vel_xy, "_VELXY_", 6, AC_PosControl, AC_PID_2D),
171 
172  // @Param: _ANGLE_MAX
173  // @DisplayName: Position Control Angle Max
174  // @Description: Maximum lean angle autopilot can request. Set to zero to use ANGLE_MAX parameter value
175  // @Units: deg
176  // @Range: 0 45
177  // @Increment: 1
178  // @User: Advanced
179  AP_GROUPINFO("_ANGLE_MAX", 7, AC_PosControl, _lean_angle_max, 0.0f),
180 
182 };
183 
184 // Default constructor.
185 // Note that the Vector/Matrix constructors already implicitly zero
186 // their values.
187 //
189  const AP_Motors& motors, AC_AttitudeControl& attitude_control) :
190  _ahrs(ahrs),
191  _inav(inav),
192  _motors(motors),
193  _attitude_control(attitude_control),
194  _p_pos_z(POSCONTROL_POS_Z_P),
195  _p_vel_z(POSCONTROL_VEL_Z_P),
197  _p_pos_xy(POSCONTROL_POS_XY_P),
199  _dt(POSCONTROL_DT_400HZ),
200  _last_update_xy_ms(0),
201  _last_update_z_ms(0),
202  _speed_down_cms(POSCONTROL_SPEED_DOWN),
203  _speed_up_cms(POSCONTROL_SPEED_UP),
204  _speed_cms(POSCONTROL_SPEED),
205  _accel_z_cms(POSCONTROL_ACCEL_Z),
206  _accel_last_z_cms(0.0f),
207  _accel_cms(POSCONTROL_ACCEL_XY),
209  _leash_down_z(POSCONTROL_LEASH_LENGTH_MIN),
210  _leash_up_z(POSCONTROL_LEASH_LENGTH_MIN),
211  _roll_target(0.0f),
212  _pitch_target(0.0f),
213  _distance_to_target(0.0f),
214  _accel_target_filter(POSCONTROL_ACCEL_FILTER_HZ)
215 {
217 
218  // initialise flags
219  _flags.recalc_leash_z = true;
220  _flags.recalc_leash_xy = true;
225  _flags.freeze_ff_z = true;
226  _flags.use_desvel_ff_z = true;
227  _limit.pos_up = true;
228  _limit.pos_down = true;
229  _limit.vel_up = true;
230  _limit.vel_down = true;
231  _limit.accel_xy = true;
232 }
233 
237 
238 
240 void AC_PosControl::set_dt(float delta_sec)
241 {
242  _dt = delta_sec;
243 
244  // update PID controller dt
247 
248  // update rate z-axis velocity error and accel error filters
250 }
251 
256 void AC_PosControl::set_speed_z(float speed_down, float speed_up)
257 {
258  // ensure speed_down is always negative
259  speed_down = -fabsf(speed_down);
260 
261  if ((fabsf(_speed_down_cms-speed_down) > 1.0f) || (fabsf(_speed_up_cms-speed_up) > 1.0f)) {
262  _speed_down_cms = speed_down;
263  _speed_up_cms = speed_up;
264  _flags.recalc_leash_z = true;
266  }
267 }
268 
270 void AC_PosControl::set_accel_z(float accel_cmss)
271 {
272  if (fabsf(_accel_z_cms-accel_cmss) > 1.0f) {
273  _accel_z_cms = accel_cmss;
274  _flags.recalc_leash_z = true;
276  }
277 }
278 
283 void AC_PosControl::set_alt_target_with_slew(float alt_cm, float dt)
284 {
285  float alt_change = alt_cm-_pos_target.z;
286 
287  // do not use z-axis desired velocity feed forward
288  _flags.use_desvel_ff_z = false;
289 
290  // adjust desired alt if motors have not hit their limits
291  if ((alt_change<0 && !_motors.limit.throttle_lower) || (alt_change>0 && !_motors.limit.throttle_upper)) {
292  if (!is_zero(dt)) {
293  float climb_rate_cms = constrain_float(alt_change/dt, _speed_down_cms, _speed_up_cms);
294  _pos_target.z += climb_rate_cms*dt;
295  _vel_desired.z = climb_rate_cms; // recorded for reporting purposes
296  }
297  }
298 
299  // do not let target get too far from current altitude
300  float curr_alt = _inav.get_altitude();
302 }
303 
304 
309 void AC_PosControl::set_alt_target_from_climb_rate(float climb_rate_cms, float dt, bool force_descend)
310 {
311  // adjust desired alt if motors have not hit their limits
312  // To-Do: add check of _limit.pos_down?
313  if ((climb_rate_cms<0 && (!_motors.limit.throttle_lower || force_descend)) || (climb_rate_cms>0 && !_motors.limit.throttle_upper && !_limit.pos_up)) {
314  _pos_target.z += climb_rate_cms * dt;
315  }
316 
317  // do not use z-axis desired velocity feed forward
318  // vel_desired set to desired climb rate for reporting and land-detector
319  _flags.use_desvel_ff_z = false;
320  _vel_desired.z = climb_rate_cms;
321 }
322 
328 void AC_PosControl::set_alt_target_from_climb_rate_ff(float climb_rate_cms, float dt, bool force_descend)
329 {
330  // calculated increased maximum acceleration if over speed
331  float accel_z_cms = _accel_z_cms;
334  }
337  }
338  accel_z_cms = constrain_float(accel_z_cms, 0.0f, 750.0f);
339 
340  // jerk_z is calculated to reach full acceleration in 1000ms.
341  float jerk_z = accel_z_cms * POSCONTROL_JERK_RATIO;
342 
343  float accel_z_max = MIN(accel_z_cms, safe_sqrt(2.0f*fabsf(_vel_desired.z - climb_rate_cms)*jerk_z));
344 
345  _accel_last_z_cms += jerk_z * dt;
346  _accel_last_z_cms = MIN(accel_z_max, _accel_last_z_cms);
347 
348  float vel_change_limit = _accel_last_z_cms * dt;
349  _vel_desired.z = constrain_float(climb_rate_cms, _vel_desired.z-vel_change_limit, _vel_desired.z+vel_change_limit);
350  _flags.use_desvel_ff_z = true;
351 
352  // adjust desired alt if motors have not hit their limits
353  // To-Do: add check of _limit.pos_down?
354  if ((_vel_desired.z<0 && (!_motors.limit.throttle_lower || force_descend)) || (_vel_desired.z>0 && !_motors.limit.throttle_upper && !_limit.pos_up)) {
355  _pos_target.z += _vel_desired.z * dt;
356  }
357 }
358 
362 void AC_PosControl::add_takeoff_climb_rate(float climb_rate_cms, float dt)
363 {
364  _pos_target.z += climb_rate_cms * dt;
365 }
366 
369 {
370  _pos_target.z += z_cm;
371 
372  // freeze feedforward to avoid jump
373  if (!is_zero(z_cm)) {
374  freeze_ff_z();
375  }
376 }
377 
379 void AC_PosControl::relax_alt_hold_controllers(float throttle_setting)
380 {
382  _vel_desired.z = 0.0f;
383  _flags.use_desvel_ff_z = false;
386  _accel_desired.z = 0.0f;
387  _accel_last_z_cms = 0.0f;
390  _pid_accel_z.set_integrator((throttle_setting-_motors.get_throttle_hover())*1000.0f);
391 }
392 
393 // get_alt_error - returns altitude error in cm
395 {
396  return (_pos_target.z - _inav.get_altitude());
397 }
398 
401 {
402  // check if z leash needs to be recalculated
404 
406 }
407 
410 {
411  const float curr_pos_z = _inav.get_altitude();
412  float curr_vel_z = _inav.get_velocity_z();
413 
414  float linear_distance; // half the distance we swap between linear and sqrt and the distance we offset sqrt
415  float linear_velocity; // the velocity we swap between linear and sqrt
416 
417  // if position controller is active add current velocity error to avoid sudden jump in acceleration
418  if (is_active_z()) {
419  curr_vel_z += _vel_error.z;
420  if (_flags.use_desvel_ff_z) {
421  curr_vel_z -= _vel_desired.z;
422  }
423  }
424 
425  // avoid divide by zero by using current position if kP is very low or acceleration is zero
426  if (_p_pos_z.kP() <= 0.0f || _accel_z_cms <= 0.0f) {
427  stopping_point.z = curr_pos_z;
428  return;
429  }
430 
431  // calculate the velocity at which we switch from calculating the stopping point using a linear function to a sqrt function
432  linear_velocity = _accel_z_cms/_p_pos_z.kP();
433 
434  if (fabsf(curr_vel_z) < linear_velocity) {
435  // if our current velocity is below the cross-over point we use a linear function
436  stopping_point.z = curr_pos_z + curr_vel_z/_p_pos_z.kP();
437  } else {
438  linear_distance = _accel_z_cms/(2.0f*_p_pos_z.kP()*_p_pos_z.kP());
439  if (curr_vel_z > 0){
440  stopping_point.z = curr_pos_z + (linear_distance + curr_vel_z*curr_vel_z/(2.0f*_accel_z_cms));
441  } else {
442  stopping_point.z = curr_pos_z - (linear_distance + curr_vel_z*curr_vel_z/(2.0f*_accel_z_cms));
443  }
444  }
445  stopping_point.z = constrain_float(stopping_point.z, curr_pos_z - POSCONTROL_STOPPING_DIST_DOWN_MAX, curr_pos_z + POSCONTROL_STOPPING_DIST_UP_MAX);
446 }
447 
450 {
451  const Vector3f& curr_pos = _inav.get_position();
452 
453  _pos_target.z = curr_pos.z;
454 
455  // freeze feedforward to avoid jump
456  freeze_ff_z();
457 
458  // shift difference between last motor out and hover throttle into accelerometer I
460 
461  // initialise ekf reset handler
463 }
464 
465 // is_active_z - returns true if the z-axis position controller has been run very recently
467 {
469 }
470 
473 {
474  // check time since last cast
475  uint32_t now = AP_HAL::millis();
479  }
480  _last_update_z_ms = now;
481 
482  // check for ekf altitude reset
484 
485  // check if leash lengths need to be recalculated
487 
488  // call z-axis position controller
490 }
491 
495 {
496  if (_flags.recalc_leash_z) {
499  _flags.recalc_leash_z = false;
500  }
501 }
502 
503 // run position control for Z axis
504 // target altitude should be set with one of these functions: set_alt_target, set_target_to_stopping_point_z, init_takeoff
505 // calculates desired rate in earth-frame z axis and passes to rate controller
506 // vel_up_max, vel_down_max should have already been set before calling this method
508 {
509  float curr_alt = _inav.get_altitude();
510 
511  // clear position limit flags
512  _limit.pos_up = false;
513  _limit.pos_down = false;
514 
515  // calculate altitude error
516  _pos_error.z = _pos_target.z - curr_alt;
517 
518  // do not let target altitude get too far from current altitude
519  if (_pos_error.z > _leash_up_z) {
520  _pos_target.z = curr_alt + _leash_up_z;
522  _limit.pos_up = true;
523  }
524  if (_pos_error.z < -_leash_down_z) {
525  _pos_target.z = curr_alt - _leash_down_z;
527  _limit.pos_down = true;
528  }
529 
530  // calculate _vel_target.z using from _pos_error.z using sqrt controller
532 
533  // check speed limits
534  // To-Do: check these speed limits here or in the pos->rate controller
535  _limit.vel_up = false;
536  _limit.vel_down = false;
537  if (_vel_target.z < _speed_down_cms) {
539  _limit.vel_down = true;
540  }
541  if (_vel_target.z > _speed_up_cms) {
543  _limit.vel_up = true;
544  }
545 
546  // add feed forward component
547  if (_flags.use_desvel_ff_z) {
549  }
550 
551  // the following section calculates acceleration required to achieve the velocity target
552 
553  const Vector3f& curr_vel = _inav.get_velocity();
554 
555  // TODO: remove velocity derivative calculation
556  // reset last velocity target to current target
559  }
560 
561  // feed forward desired acceleration calculation
562  if (_dt > 0.0f) {
563  if (!_flags.freeze_ff_z) {
565  } else {
566  // stop the feed forward being calculated during a known discontinuity
567  _flags.freeze_ff_z = false;
568  }
569  } else {
570  _accel_desired.z = 0.0f;
571  }
572 
573  // store this iteration's velocities for the next iteration
575 
576  // reset velocity error and filter if this controller has just been engaged
578  // Reset Filter
579  _vel_error.z = 0;
582  } else {
583  // calculate rate error and filter with cut off frequency of 2 Hz
585  }
586 
588 
590 
591 
592  // the following section calculates a desired throttle needed to achieve the acceleration target
593  float z_accel_meas; // actual acceleration
594  float p,i,d; // used to capture pid values for logging
595 
596  // Calculate Earth Frame Z acceleration
597  z_accel_meas = -(_ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f;
598 
599  // reset target altitude if this controller has just been engaged
601  // Reset Filter
602  _accel_error.z = 0;
604  } else {
605  // calculate accel error
606  _accel_error.z = _accel_target.z - z_accel_meas;
607  }
608 
609  // set input to PID
612 
613  // separately calculate p, i, d values for logging
614  p = _pid_accel_z.get_p();
615 
616  // get i term
618 
619  // ensure imax is always large enough to overpower hover throttle
620  if (_motors.get_throttle_hover() * 1000.0f > _pid_accel_z.imax()) {
622  }
623 
624  // update i term as long as we haven't breached the limits or the I term will certainly reduce
625  // To-Do: should this be replaced with limits check from attitude_controller?
626  if ((!_motors.limit.throttle_lower && !_motors.limit.throttle_upper) || (i>0&&_accel_error.z<0) || (i<0&&_accel_error.z>0)) {
627  i = _pid_accel_z.get_i();
628  }
629 
630  // get d term
631  d = _pid_accel_z.get_d();
632 
633  float thr_out = (p+i+d)*0.001f +_motors.get_throttle_hover();
634 
635  // send throttle to attitude controller with angle boost
637 }
638 
642 
644 void AC_PosControl::set_accel_xy(float accel_cmss)
645 {
646  if (fabsf(_accel_cms-accel_cmss) > 1.0f) {
647  _accel_cms = accel_cmss;
648  _flags.recalc_leash_xy = true;
650  }
651 }
652 
654 void AC_PosControl::set_speed_xy(float speed_cms)
655 {
656  if (fabsf(_speed_cms-speed_cms) > 1.0f) {
657  _speed_cms = speed_cms;
658  _flags.recalc_leash_xy = true;
660  }
661 }
662 
665 {
666  _pos_target = position;
667 
668  _flags.use_desvel_ff_z = false;
669  _vel_desired.z = 0.0f;
670  // initialise roll and pitch to current roll and pitch. This avoids a twitch between when the target is set and the pos controller is first run
671  // To-Do: this initialisation of roll and pitch targets needs to go somewhere between when pos-control is initialised and when it completes it's first cycle
672  //_roll_target = constrain_int32(_ahrs.roll_sensor,-_attitude_control.lean_angle_max(),_attitude_control.lean_angle_max());
673  //_pitch_target = constrain_int32(_ahrs.pitch_sensor,-_attitude_control.lean_angle_max(),_attitude_control.lean_angle_max());
674 }
675 
677 void AC_PosControl::set_xy_target(float x, float y)
678 {
679  _pos_target.x = x;
680  _pos_target.y = y;
681 }
682 
684 void AC_PosControl::shift_pos_xy_target(float x_cm, float y_cm)
685 {
686  // move pos controller target
687  _pos_target.x += x_cm;
688  _pos_target.y += y_cm;
689 }
690 
693 {
694  // check if xy leash needs to be recalculated
696 
698 }
699 
706 {
707  const Vector3f curr_pos = _inav.get_position();
708  Vector3f curr_vel = _inav.get_velocity();
709  float linear_distance; // the distance at which we swap from a linear to sqrt response
710  float linear_velocity; // the velocity above which we swap from a linear to sqrt response
711  float stopping_dist; // the distance within the vehicle can stop
712  float kP = _p_pos_xy.kP();
713 
714  // add velocity error to current velocity
715  if (is_active_xy()) {
716  curr_vel.x += _vel_error.x;
717  curr_vel.y += _vel_error.y;
718  }
719 
720  // calculate current velocity
721  float vel_total = norm(curr_vel.x, curr_vel.y);
722 
723  // avoid divide by zero by using current position if the velocity is below 10cm/s, kP is very low or acceleration is zero
724  if (kP <= 0.0f || _accel_cms <= 0.0f || is_zero(vel_total)) {
725  stopping_point.x = curr_pos.x;
726  stopping_point.y = curr_pos.y;
727  return;
728  }
729 
730  // calculate point at which velocity switches from linear to sqrt
731  linear_velocity = _accel_cms/kP;
732 
733  // calculate distance within which we can stop
734  if (vel_total < linear_velocity) {
735  stopping_dist = vel_total/kP;
736  } else {
737  linear_distance = _accel_cms/(2.0f*kP*kP);
738  stopping_dist = linear_distance + (vel_total*vel_total)/(2.0f*_accel_cms);
739  }
740 
741  // constrain stopping distance
742  stopping_dist = constrain_float(stopping_dist, 0, _leash);
743 
744  // convert the stopping distance into a stopping point using velocity vector
745  stopping_point.x = curr_pos.x + (stopping_dist * curr_vel.x / vel_total);
746  stopping_point.y = curr_pos.y + (stopping_dist * curr_vel.y / vel_total);
747 }
748 
751 {
752  return _distance_to_target;
753 }
754 
757 {
759 }
760 
761 // is_active_xy - returns true if the xy position controller has been run very recently
763 {
765 }
766 
769 {
770  if (is_zero(_lean_angle_max)) {
772  }
773  return _lean_angle_max * 100.0f;
774 }
775 
781 {
782  // set roll, pitch lean angle targets to current attitude
785 
786  // initialise I terms from lean angles
787  if (reset_I) {
788  // reset last velocity if this controller has just been engaged or dt is zero
791  }
792 
793  // flag reset required in rate to accel step
796 
797  // initialise ekf xy reset handler
799 }
800 
802 void AC_PosControl::update_xy_controller(float ekfNavVelGainScaler)
803 {
804  // compute dt
805  uint32_t now = AP_HAL::millis();
806  float dt = (now - _last_update_xy_ms)*0.001f;
807 
808  // sanity check dt
809  if (dt >= POSCONTROL_ACTIVE_TIMEOUT_MS*1.0e-3f) {
810  dt = 0.0f;
811  }
812 
813  // check for ekf xy position reset
815 
816  // check if xy leash needs to be recalculated
818 
819  // translate any adjustments from pilot to loiter target
820  desired_vel_to_pos(dt);
821 
822  // run horizontal position controller
823  run_xy_controller(dt, ekfNavVelGainScaler);
824 
825  // update xy update time
826  _last_update_xy_ms = now;
827 }
828 
830 {
831  uint32_t now = AP_HAL::millis();
832  return (now - _last_update_xy_ms)*0.001f;
833 }
834 
835 // write log to dataflash
837 {
838  const Vector3f &pos_target = get_pos_target();
839  const Vector3f &vel_target = get_vel_target();
840  const Vector3f &accel_target = get_accel_target();
841  const Vector3f &position = _inav.get_position();
842  const Vector3f &velocity = _inav.get_velocity();
843  float accel_x, accel_y;
844  lean_angles_to_accel(accel_x, accel_y);
845 
846  DataFlash_Class::instance()->Log_Write("PSC", "TimeUS,TPX,TPY,PX,PY,TVX,TVY,VX,VY,TAX,TAY,AX,AY",
847  "smmmmnnnnoooo", "FBBBBBBBBBBBB", "Qffffffffffff",
849  (double)pos_target.x,
850  (double)pos_target.y,
851  (double)position.x,
852  (double)position.y,
853  (double)vel_target.x,
854  (double)vel_target.y,
855  (double)velocity.x,
856  (double)velocity.y,
857  (double)accel_target.x,
858  (double)accel_target.y,
859  (double)accel_x,
860  (double)accel_y);
861 }
862 
865 {
866  // set roll, pitch lean angle targets to current attitude
869 
870  // reset last velocity if this controller has just been engaged or dt is zero
873 
874  // flag reset required in rate to accel step
877 
878  // set target position
879  const Vector3f& curr_pos = _inav.get_position();
880  set_xy_target(curr_pos.x, curr_pos.y);
881  set_alt_target(curr_pos.z);
882 
883  // move current vehicle velocity into feed forward velocity
884  const Vector3f& curr_vel = _inav.get_velocity();
885  set_desired_velocity(curr_vel);
886 
887  // set vehicle acceleration to zero
888  set_desired_accel_xy(0.0f,0.0f);
889 
890  // initialise ekf reset handlers
893 }
894 
899 void AC_PosControl::update_vel_controller_xy(float ekfNavVelGainScaler)
900 {
901  // capture time since last iteration
902  uint32_t now = AP_HAL::millis();
903  float dt = (now - _last_update_xy_ms)*0.001f;
904 
905  // sanity check dt
906  if (dt >= 0.2f) {
907  dt = 0.0f;
908  }
909 
910  // check for ekf xy position reset
912 
913  // check if xy leash needs to be recalculated
915 
916  // apply desired velocity request to position target
917  // TODO: this will need to be removed and added to the calling function.
918  desired_vel_to_pos(dt);
919 
920  // run position controller
921  run_xy_controller(dt, ekfNavVelGainScaler);
922 
923  // update xy update time
924  _last_update_xy_ms = now;
925 }
926 
927 
932 void AC_PosControl::update_vel_controller_xyz(float ekfNavVelGainScaler)
933 {
934  update_vel_controller_xy(ekfNavVelGainScaler);
935 
936  // update altitude target
938 
939  // run z-axis position controller
941 }
942 
944 {
945  return norm(_pos_error.x, _pos_error.y);
946 }
947 
951 
955 {
956  // todo: remove _flags.recalc_leash_xy or don't call this function after each variable change.
957  if (_flags.recalc_leash_xy) {
959  _flags.recalc_leash_xy = false;
960  }
961 }
962 
965 {
966  // range check nav_dt
967  if (nav_dt < 0) {
968  return;
969  }
970 
971  // update target velocity
974  } else {
975  _vel_desired.x += _accel_desired.x * nav_dt;
976  _vel_desired.y += _accel_desired.y * nav_dt;
977  }
978 }
979 
982 {
983  // range check nav_dt
984  if( nav_dt < 0 ) {
985  return;
986  }
987 
988  // update target position
991  } else {
992  _pos_target.x += _vel_desired.x * nav_dt;
993  _pos_target.y += _vel_desired.y * nav_dt;
994  }
995 }
996 
1002 void AC_PosControl::run_xy_controller(float dt, float ekfNavVelGainScaler)
1003 {
1004  Vector3f curr_pos = _inav.get_position();
1005  float kP = ekfNavVelGainScaler * _p_pos_xy.kP(); // scale gains to compensate for noisy optical flow measurement in the EKF
1006 
1007  // avoid divide by zero
1008  if (kP <= 0.0f) {
1009  _vel_target.x = 0.0f;
1010  _vel_target.y = 0.0f;
1011  }else{
1012  // calculate distance error
1013  _pos_error.x = _pos_target.x - curr_pos.x;
1014  _pos_error.y = _pos_target.y - curr_pos.y;
1015 
1016  // Constrain _pos_error and target position
1017  // Constrain the maximum length of _vel_target to the maximum position correction velocity
1018  // TODO: replace the leash length with a user definable maximum position correction
1020  {
1021  _pos_target.x = curr_pos.x + _pos_error.x;
1022  _pos_target.y = curr_pos.y + _pos_error.y;
1023  }
1025 
1027  }
1028 
1029  // add velocity feed-forward
1032 
1033  // the following section converts desired velocities in lat/lon directions to accelerations in lat/lon frame
1034 
1035  Vector2f accel_target, vel_xy_p, vel_xy_i, vel_xy_d;
1036 
1037  // check if vehicle velocity is being overridden
1040  } else {
1043  }
1044 
1045  // calculate velocity error
1048  // TODO: constrain velocity error and velocity target
1049 
1050  // call pi controller
1052 
1053  // get p
1054  vel_xy_p = _pid_vel_xy.get_p();
1055 
1056  // update i term if we have not hit the accel or throttle limits OR the i term will reduce
1057  // TODO: move limit handling into the PI and PID controller
1059  vel_xy_i = _pid_vel_xy.get_i();
1060  } else {
1061  vel_xy_i = _pid_vel_xy.get_i_shrink();
1062  }
1063 
1064  // get d
1065  vel_xy_d = _pid_vel_xy.get_d();
1066 
1067 
1068  // acceleration to correct for velocity error and scale PID output to compensate for optical flow measurement induced EKF noise
1069  accel_target.x = (vel_xy_p.x + vel_xy_i.x + vel_xy_d.x) * ekfNavVelGainScaler;
1070  accel_target.y = (vel_xy_p.y + vel_xy_i.y + vel_xy_d.y) * ekfNavVelGainScaler;
1071 
1072  // reset accel to current desired acceleration
1074  _accel_target_filter.reset(Vector2f(accel_target.x, accel_target.y));
1076  }
1077 
1078  // filter correction acceleration
1080  _accel_target_filter.apply(accel_target, dt);
1081 
1082  // pass the correction acceleration to the target acceleration output
1085 
1086  // Add feed forward into the target acceleration output
1089 
1090  // the following section converts desired accelerations provided in lat/lon frame to roll/pitch angles
1091 
1092  // limit acceleration using maximum lean angles
1094  float accel_max = MIN(GRAVITY_MSS * 100.0f * tanf(ToRad(angle_max * 0.01f)), POSCONTROL_ACCEL_XY_MAX);
1096 
1097  // update angle targets that will be passed to stabilize controller
1099 }
1100 
1101 // get_lean_angles_to_accel - convert roll, pitch lean angles to lat/lon frame accelerations in cm/s/s
1102 void AC_PosControl::accel_to_lean_angles(float accel_x_cmss, float accel_y_cmss, float& roll_target, float& pitch_target) const
1103 {
1104  float accel_right, accel_forward;
1105 
1106  // rotate accelerations into body forward-right frame
1107  accel_forward = accel_x_cmss*_ahrs.cos_yaw() + accel_y_cmss*_ahrs.sin_yaw();
1108  accel_right = -accel_x_cmss*_ahrs.sin_yaw() + accel_y_cmss*_ahrs.cos_yaw();
1109 
1110  // update angle targets that will be passed to stabilize controller
1111  pitch_target = atanf(-accel_forward/(GRAVITY_MSS * 100.0f))*(18000.0f/M_PI);
1112  float cos_pitch_target = cosf(pitch_target*M_PI/18000.0f);
1113  roll_target = atanf(accel_right*cos_pitch_target/(GRAVITY_MSS * 100.0f))*(18000.0f/M_PI);
1114 }
1115 
1116 // get_lean_angles_to_accel - convert roll, pitch lean angles to lat/lon frame accelerations in cm/s/s
1117 void AC_PosControl::lean_angles_to_accel(float& accel_x_cmss, float& accel_y_cmss) const
1118 {
1119  // rotate our roll, pitch angles into lat/lon frame
1120  accel_x_cmss = (GRAVITY_MSS * 100) * (-_ahrs.cos_yaw() * _ahrs.sin_pitch() * _ahrs.cos_roll() - _ahrs.sin_yaw() * _ahrs.sin_roll()) / MAX(_ahrs.cos_roll()*_ahrs.cos_pitch(), 0.5f);
1121  accel_y_cmss = (GRAVITY_MSS * 100) * (-_ahrs.sin_yaw() * _ahrs.sin_pitch() * _ahrs.cos_roll() + _ahrs.cos_yaw() * _ahrs.sin_roll()) / MAX(_ahrs.cos_roll()*_ahrs.cos_pitch(), 0.5f);
1122 }
1123 
1125 float AC_PosControl::calc_leash_length(float speed_cms, float accel_cms, float kP) const
1126 {
1127  float leash_length;
1128 
1129  // sanity check acceleration and avoid divide by zero
1130  if (accel_cms <= 0.0f) {
1131  accel_cms = POSCONTROL_ACCELERATION_MIN;
1132  }
1133 
1134  // avoid divide by zero
1135  if (kP <= 0.0f) {
1137  }
1138 
1139  // calculate leash length
1140  if(speed_cms <= accel_cms / kP) {
1141  // linear leash length based on speed close in
1142  leash_length = speed_cms / kP;
1143  }else{
1144  // leash length grows at sqrt of speed further out
1145  leash_length = (accel_cms / (2.0f*kP*kP)) + (speed_cms*speed_cms / (2.0f*accel_cms));
1146  }
1147 
1148  // ensure leash is at least 1m long
1149  if( leash_length < POSCONTROL_LEASH_LENGTH_MIN ) {
1150  leash_length = POSCONTROL_LEASH_LENGTH_MIN;
1151  }
1152 
1153  return leash_length;
1154 }
1155 
1158 {
1159  Vector2f pos_shift;
1161 }
1162 
1165 {
1166  // check for position shift
1167  Vector2f pos_shift;
1168  uint32_t reset_ms = _ahrs.getLastPosNorthEastReset(pos_shift);
1169  if (reset_ms != _ekf_xy_reset_ms) {
1170  shift_pos_xy_target(pos_shift.x * 100.0f, pos_shift.y * 100.0f);
1171  _ekf_xy_reset_ms = reset_ms;
1172  }
1173 }
1174 
1177 {
1178  float alt_shift;
1180 }
1181 
1184 {
1185  // check for position shift
1186  float alt_shift;
1187  uint32_t reset_ms = _ahrs.getLastPosDownReset(alt_shift);
1188  if (reset_ms != 0 && reset_ms != _ekf_z_reset_ms) {
1189  shift_alt_target(-alt_shift * 100.0f);
1190  _ekf_z_reset_ms = reset_ms;
1191  }
1192 }
1193 
1194 
1196 bool AC_PosControl::limit_vector_length(float& vector_x, float& vector_y, float max_length)
1197 {
1198  float vector_length = norm(vector_x, vector_y);
1199  if ((vector_length > max_length) && is_positive(max_length)) {
1200  vector_x *= (max_length / vector_length);
1201  vector_y *= (max_length / vector_length);
1202  return true;
1203  }
1204  return false;
1205 }
1206 
1207 
1209 Vector3f AC_PosControl::sqrt_controller(const Vector3f& error, float p, float second_ord_lim)
1210 {
1211  if (second_ord_lim < 0.0f || is_zero(second_ord_lim) || is_zero(p)) {
1212  return Vector3f(error.x*p, error.y*p, error.z);
1213  }
1214 
1215  float linear_dist = second_ord_lim/sq(p);
1216  float error_length = norm(error.x, error.y);
1217  if (error_length > linear_dist) {
1218  float first_order_scale = safe_sqrt(2.0f*second_ord_lim*(error_length-(linear_dist * 0.5f)))/error_length;
1219  return Vector3f(error.x*first_order_scale, error.y*first_order_scale, error.z);
1220  } else {
1221  return Vector3f(error.x*p, error.y*p, error.z);
1222  }
1223 }
void reset(T value)
float norm(const T first, const U second, const Params... parameters)
Definition: AP_Math.h:190
#define POSCONTROL_ACCEL_FILTER_HZ
Definition: AC_PosControl.h:38
#define POSCONTROL_ACC_Z_IMAX
void get_stopping_point_xy(Vector3f &stopping_point) const
Vector2< float > Vector2f
Definition: vector2.h:239
uint32_t _last_update_z_ms
void init_takeoff()
init_takeoff - initialises target altitude if we are taking off
virtual float get_velocity_z() const =0
#define POSCONTROL_LEASH_LENGTH_MIN
Definition: AC_PosControl.h:29
void set_integrator(const Vector2f &i)
Definition: AC_PID_2D.h:65
void run_z_controller()
const AP_Motors & _motors
float get_lean_angle_max_cd() const
get_lean_angle_max_cd - returns the maximum lean angle the autopilot may request
Vector3< float > Vector3f
Definition: vector3.h:246
void init_ekf_xy_reset()
initialise and check for ekf position resets
void shift_pos_xy_target(float x_cm, float y_cm)
shift position target target in x, y axis
virtual const Vector3f & get_position() const =0
int32_t pitch_sensor
Definition: AP_AHRS_View.h:172
#define POSCONTROL_ACC_Z_DT
void set_alt_target_with_slew(float alt_cm, float dt)
float safe_sqrt(const T v)
Definition: AP_Math.cpp:64
const Vector3f & get_accel_target() const
#define POSCONTROL_DT_50HZ
Definition: AC_PosControl.h:31
float _distance_to_target
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
const Vector3f & get_vel_target() const
accessors for reporting
Vector2f get_p() const
Definition: AC_PID_2D.cpp:147
#define POSCONTROL_ACCEL_XY
Definition: AC_PosControl.h:18
static const struct AP_Param::GroupInfo var_info[]
float get_distance_to_target() const
get_distance_to_target - get horizontal distance to position target in cm (used for reporting) ...
virtual void set_alt_target_from_climb_rate(float climb_rate_cms, float dt, bool force_descend)
float get_althold_lean_angle_max() const
#define POSCONTROL_VEL_ERROR_CUTOFF_FREQ
Definition: AC_PosControl.h:36
float get_alt_error() const
get_alt_error - returns altitude error in cm
void get_stopping_point_z(Vector3f &stopping_point) const
get_stopping_point_z - calculates stopping point based on current position, velocity, vehicle acceleration
#define POSCONTROL_SPEED
Definition: AC_PosControl.h:23
const AP_AHRS_View & _ahrs
void set_input(const Vector2f &input)
Definition: AC_PID_2D.cpp:102
#define ToRad(x)
Definition: AP_Common.h:53
virtual void set_throttle_out(float throttle_in, bool apply_angle_boost, float filt_cutoff)=0
#define POSCONTROL_ACC_Z_FILT_HZ
void update_z_controller()
update_z_controller - fly to altitude in cm above home
void set_desired_accel_xy(float accel_lat_cms, float accel_lon_cms)
void init_vel_controller_xyz()
xyz velocity controller
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
struct AP_Motors::AP_Motors_limit limit
#define POSCONTROL_VEL_Z_P
void run_xy_controller(float dt, float ekfNavVelGainScaler)
AC_PosControl(const AP_AHRS_View &ahrs, const AP_InertialNav &inav, const AP_Motors &motors, AC_AttitudeControl &attitude_control)
Constructor.
void update_xy_controller(float ekfNavVelGainScaler)
update_xy_controller - run the horizontal position controller - should be called at 100hz or higher ...
float get_d()
Definition: AC_PID.cpp:155
float get_horizontal_error() const
Vector3f _pos_error
const AP_HAL::HAL & hal
Definition: UARTDriver.cpp:37
#define POSCONTROL_SPEED_UP
Definition: AC_PosControl.h:25
static Vector3f sqrt_controller(const Vector3f &error, float p, float second_ord_lim)
Proportional controller with piecewise sqrt sections to constrain second derivative.
#define POSCONTROL_ACTIVE_TIMEOUT_MS
Definition: AC_PosControl.h:34
LowPassFilterVector2f _accel_target_filter
bool is_positive(const T fVal1)
Definition: AP_Math.h:50
#define POSCONTROL_VEL_XY_I
#define POSCONTROL_STOPPING_DIST_DOWN_MAX
Definition: AC_PosControl.h:21
const Vector3f & get_accel_ef_blended(void) const
Definition: AP_AHRS_View.h:136
Vector3f _vel_desired
float _speed_down_cms
#define POSCONTROL_ACC_Z_I
void update_vel_controller_xy(float ekfNavVelGainScaler)
#define POSCONTROL_DT_400HZ
Definition: AC_PosControl.h:32
#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
uint32_t _ekf_z_reset_ms
void set_integrator(float i)
Definition: AC_PID.h:77
void set_cutoff_frequency(float cutoff_freq)
#define POSCONTROL_POS_XY_P
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
void set_xy_target(float x, float y)
set_xy_target in cm from home
Vector2f get_d()
Definition: AC_PID_2D.cpp:180
AP_MotorsMatrix motors(400)
Vector3f _pos_target
void add_takeoff_climb_rate(float climb_rate_cms, float dt)
void update_vel_controller_xyz(float ekfNavVelGainScaler)
Object managing one P controller.
Definition: AC_P.h:13
bool is_active_xy() const
#define POSCONTROL_VEL_XY_IMAX
T y
Definition: vector2.h:37
Vector2f get_i_shrink()
Definition: AC_PID_2D.cpp:166
void desired_vel_to_pos(float nav_dt)
desired_vel_to_pos - move position target using desired velocities
#define POSCONTROL_POS_Z_P
void set_dt(float dt)
Definition: AC_PID_2D.cpp:67
#define x(i)
bool is_active_z() const
float lean_angle_max() const
#define POSCONTROL_SPEED_DOWN
Definition: AC_PosControl.h:24
void check_for_ekf_xy_reset()
check for ekf position reset and adjust loiter or brake target position
void relax_alt_hold_controllers(float throttle_setting)
relax_alt_hold_controllers - set all desired and targets to measured
void lean_angles_to_accel(float &accel_x_cmss, float &accel_y_cmss) const
uint32_t getLastPosDownReset(float &posDelta) const
Definition: AP_AHRS_View.h:144
const Vector3f & get_pos_target() const
get_pos_target - get target as position vector (from home in cm)
void Log_Write(const char *name, const char *labels, const char *fmt,...)
Definition: DataFlash.cpp:632
struct AC_PosControl::poscontrol_limit_flags _limit
#define GRAVITY_MSS
Definition: definitions.h:47
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
void accel_to_lean_angles(float accel_x_cmss, float accel_y_cmss, float &roll_target, float &pitch_target) const
AC_AttitudeControl & _attitude_control
AP_Float _accel_xy_filt_hz
void init_xy_controller(bool reset_I=true)
T y
Definition: vector3.h:67
void set_speed_z(float speed_down, float speed_up)
#define POSCONTROL_JERK_RATIO
Definition: AC_PosControl.h:39
uint32_t millis()
Definition: system.cpp:157
struct AC_PosControl::poscontrol_flags _flags
void calc_leash_length_z()
static DataFlash_Class * instance(void)
Definition: DataFlash.h:62
T z
Definition: vector3.h:67
void set_desired_velocity(const Vector3f &des_vel)
uint64_t micros64()
Definition: system.cpp:162
void set_dt(float delta_sec)
set_dt - sets time delta in seconds for all controllers (i.e. 100hz = 0.01, 400hz = 0...
AP_Float _lean_angle_max
float imax() const
Definition: AC_PID.h:64
void calc_leash_length_xy()
void set_accel_z(float accel_cmss)
set_accel_z - set vertical acceleration in cm/s/s
void init_ekf_z_reset()
initialise ekf z axis reset check
static float sqrt_controller(float error, float p, float second_ord_lim, float dt)
virtual float get_throttle_hover() const =0
#define POSCONTROL_ACC_Z_P
Vector3f _vel_error
virtual void set_alt_target_from_climb_rate_ff(float climb_rate_cms, float dt, bool force_descend)
void set_pos_target(const Vector3f &position)
set_pos_target in cm from home
const AP_InertialNav & _inav
Vector2f get_i()
Definition: AC_PID_2D.cpp:152
const T & get() const
Vector3f _accel_error
void set_desired_rate(float desired)
Definition: AC_PID.h:80
#define POSCONTROL_ACC_Z_D
#define POSCONTROL_ACCEL_XY_MAX
Definition: AC_PosControl.h:19
Vector2f _vehicle_horiz_vel
#define POSCONTROL_OVERSPEED_GAIN_Z
Definition: AC_PosControl.h:41
uint32_t getLastPosNorthEastReset(Vector2f &pos) const
Definition: AP_AHRS_View.h:140
int32_t get_bearing_to_target() const
get_bearing_to_target - get bearing to target position in centi-degrees
void freeze_ff_z()
freeze_ff_z - used to stop the feed forward being calculated during a known discontinuity ...
#define POSCONTROL_THROTTLE_CUTOFF_FREQ
Definition: AC_PosControl.h:37
static bool limit_vector_length(float &vector_x, float &vector_y, float max_length)
limit vector to a given length, returns true if vector was limited
#define POSCONTROL_ACCEL_Z
Definition: AC_PosControl.h:27
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
void shift_alt_target(float z_cm)
shift altitude target (positive means move altitude up)
T x
Definition: vector2.h:37
Copter PID control class.
Definition: AC_PID_2D.h:13
Vector3f _accel_target
void set_target_to_stopping_point_xy()
set_target_to_stopping_point_xy - sets horizontal target to reasonable stopping position in cm from h...
void set_alt_target(float alt_cm)
set_alt_target - set altitude target in cm above home
Definition: AC_PosControl.h:90
void check_for_ekf_z_reset()
check for ekf position reset and adjust loiter or brake target position
void set_dt(float dt)
Definition: AC_PID.cpp:69
void set_accel_xy(float accel_cmss)
set_accel_xy - set horizontal acceleration in cm/s/s
void set_input_filter_all(float input)
Definition: AC_PID.cpp:87
uint32_t _last_update_xy_ms
#define error(fmt, args ...)
float sq(const T val)
Definition: AP_Math.h:170
AC_PID_2D _pid_vel_xy
#define POSCONTROL_ACCELERATION_MIN
Definition: AC_PosControl.h:17
void set_target_to_stopping_point_z()
set_target_to_stopping_point_z - sets altitude target to reasonable stopping altitude in cm above hom...
float time_since_last_xy_update() const
float get_p(float error) const
Definition: AC_P.cpp:15
#define POSCONTROL_VEL_XY_P
virtual const Vector3f & get_velocity() const =0
float get_integrator() const
Definition: AC_PID.h:76
float get_i()
Definition: AC_PID.cpp:140
Vector3f _vel_last
#define M_PI
Definition: definitions.h:10
float get_throttle() const
void desired_accel_to_vel(float nav_dt)
move velocity target using desired acceleration
Copter PID control class.
Definition: AC_PID.h:17
Vector3f _accel_desired
#define POSCONTROL_VEL_XY_FILT_D_HZ
int32_t roll_sensor
Definition: AP_AHRS_View.h:171
#define AP_SUBGROUPINFO(element, name, idx, thisclazz, elclazz)
Definition: AP_Param.h:109
virtual float get_altitude() const =0
float _accel_last_z_cms
void set_speed_xy(float speed_cms)
set_speed_xy - set horizontal speed maximum in cm/s
LowPassFilterFloat _vel_error_filter
AP_Float & kP()
Definition: AC_P.h:58
float get_p()
Definition: AC_PID.cpp:134
#define AP_GROUPEND
Definition: AP_Param.h:121
#define POSCONTROL_VEL_XY_D
#define POSCONTROL_STOPPING_DIST_UP_MAX
Definition: AC_PosControl.h:20
AC_PID _pid_accel_z
T x
Definition: vector3.h:67
T apply(T sample, float dt)
#define POSCONTROL_VEL_XY_FILT_HZ
uint32_t _ekf_xy_reset_ms
Vector3f _vel_target
float calc_leash_length(float speed_cms, float accel_cms, float kP) const
calc_leash_length - calculates the horizontal leash length given a maximum speed, acceleration and po...
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214