mirror of https://github.com/ArduPilot/ardupilot
AC_PosControl: Fill _vel_desired.z for reporting
This commit is contained in:
parent
2a7f78a2cd
commit
a580cd83e8
|
@ -118,6 +118,8 @@ void AC_PosControl::set_alt_target_with_slew(float alt_cm, float dt)
|
||||||
{
|
{
|
||||||
float alt_change = alt_cm-_pos_target.z;
|
float alt_change = alt_cm-_pos_target.z;
|
||||||
|
|
||||||
|
_vel_desired.z = constrain_float(alt_change * dt, _speed_down_cms, _speed_up_cms);
|
||||||
|
|
||||||
// adjust desired alt if motors have not hit their limits
|
// adjust desired alt if motors have not hit their limits
|
||||||
if ((alt_change<0 && !_motors.limit.throttle_lower) || (alt_change>0 && !_motors.limit.throttle_upper)) {
|
if ((alt_change<0 && !_motors.limit.throttle_lower) || (alt_change>0 && !_motors.limit.throttle_upper)) {
|
||||||
_pos_target.z += constrain_float(alt_change, _speed_down_cms*dt, _speed_up_cms*dt);
|
_pos_target.z += constrain_float(alt_change, _speed_down_cms*dt, _speed_up_cms*dt);
|
||||||
|
@ -139,6 +141,8 @@ void AC_PosControl::set_alt_target_from_climb_rate(float climb_rate_cms, float d
|
||||||
if ((climb_rate_cms<0 && (!_motors.limit.throttle_lower || force_descend)) || (climb_rate_cms>0 && !_motors.limit.throttle_upper)) {
|
if ((climb_rate_cms<0 && (!_motors.limit.throttle_lower || force_descend)) || (climb_rate_cms>0 && !_motors.limit.throttle_upper)) {
|
||||||
_pos_target.z += climb_rate_cms * dt;
|
_pos_target.z += climb_rate_cms * dt;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
_vel_desired.z = climb_rate_cms;
|
||||||
}
|
}
|
||||||
|
|
||||||
// get_alt_error - returns altitude error in cm
|
// get_alt_error - returns altitude error in cm
|
||||||
|
|
Loading…
Reference in New Issue