APM:Libraries
AC_PosControl_Sub.cpp
Go to the documentation of this file.
1 #include "AC_PosControl_Sub.h"
2 
4  const AP_Motors& motors, AC_AttitudeControl& attitude_control) :
5  AC_PosControl(ahrs, inav, motors, attitude_control),
6  _alt_max(0.0f),
7  _alt_min(0.0f)
8 {}
9 
14 void AC_PosControl_Sub::set_alt_target_from_climb_rate(float climb_rate_cms, float dt, bool force_descend)
15 {
16  // adjust desired alt if motors have not hit their limits
17  // To-Do: add check of _limit.pos_down?
18  if ((climb_rate_cms<0 && (!_motors.limit.throttle_lower || force_descend)) || (climb_rate_cms>0 && !_motors.limit.throttle_upper && !_limit.pos_up)) {
19  _pos_target.z += climb_rate_cms * dt;
20  }
21 
22  // do not let target alt get above limit
23  if (_alt_max < 100 && _pos_target.z > _alt_max) {
25  _limit.pos_up = true;
26  }
27 
28  // do not let target alt get below limit
29  if (_alt_min < 0 && _alt_min < _alt_max && _pos_target.z < _alt_min) {
31  _limit.pos_down = true;
32  }
33 
34  // do not use z-axis desired velocity feed forward
35  // vel_desired set to desired climb rate for reporting and land-detector
36  _flags.use_desvel_ff_z = false;
37  _vel_desired.z = climb_rate_cms;
38 }
39 
45 void AC_PosControl_Sub::set_alt_target_from_climb_rate_ff(float climb_rate_cms, float dt, bool force_descend)
46 {
47  // calculated increased maximum acceleration if over speed
48  float accel_z_cms = _accel_z_cms;
51  }
54  }
55  accel_z_cms = constrain_float(accel_z_cms, 0.0f, 750.0f);
56 
57  // jerk_z is calculated to reach full acceleration in 1000ms.
58  float jerk_z = accel_z_cms * POSCONTROL_JERK_RATIO;
59 
60  float accel_z_max = MIN(accel_z_cms, safe_sqrt(2.0f*fabsf(_vel_desired.z - climb_rate_cms)*jerk_z));
61 
62  _accel_last_z_cms += jerk_z * dt;
63  _accel_last_z_cms = MIN(accel_z_max, _accel_last_z_cms);
64 
65  float vel_change_limit = _accel_last_z_cms * dt;
66  _vel_desired.z = constrain_float(climb_rate_cms, _vel_desired.z-vel_change_limit, _vel_desired.z+vel_change_limit);
67  _flags.use_desvel_ff_z = true;
68 
69  // adjust desired alt if motors have not hit their limits
70  // To-Do: add check of _limit.pos_down?
71  if ((_vel_desired.z<0 && (!_motors.limit.throttle_lower || force_descend)) || (_vel_desired.z>0 && !_motors.limit.throttle_upper && !_limit.pos_up)) {
72  _pos_target.z += _vel_desired.z * dt;
73  }
74 
75  // do not let target alt get above limit
76  if (_alt_max < 100 && _pos_target.z > _alt_max) {
78  _limit.pos_up = true;
79  // decelerate feed forward to zero
80  _vel_desired.z = constrain_float(0.0f, _vel_desired.z-vel_change_limit, _vel_desired.z+vel_change_limit);
81  }
82 
83  // do not let target alt get below limit
84  if (_alt_min < 0 && _alt_min < _alt_max && _pos_target.z < _alt_min) {
86  _limit.pos_down = true;
87  // decelerate feed forward to zero
88  _vel_desired.z = constrain_float(0.0f, _vel_desired.z-vel_change_limit, _vel_desired.z+vel_change_limit);
89  }
90 }
const AP_Motors & _motors
float safe_sqrt(const T v)
Definition: AP_Math.cpp:64
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
struct AP_Motors::AP_Motors_limit limit
Vector3f _vel_desired
float _speed_down_cms
#define MIN(a, b)
Definition: usb_conf.h:215
AP_MotorsMatrix motors(400)
Vector3f _pos_target
struct AC_PosControl::poscontrol_limit_flags _limit
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
#define POSCONTROL_JERK_RATIO
Definition: AC_PosControl.h:39
struct AC_PosControl::poscontrol_flags _flags
T z
Definition: vector3.h:67
#define POSCONTROL_OVERSPEED_GAIN_Z
Definition: AC_PosControl.h:41
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
void set_alt_target_from_climb_rate(float climb_rate_cms, float dt, bool force_descend) override
void set_alt_target_from_climb_rate_ff(float climb_rate_cms, float dt, bool force_descend) override
float _accel_last_z_cms
AC_PosControl_Sub(const AP_AHRS_View &ahrs, const AP_InertialNav &inav, const AP_Motors &motors, AC_AttitudeControl &attitude_control)