mirror of https://github.com/ArduPilot/ardupilot
AC_PosControl: add_takeoff_climb_rate method
This function simply increments the current altitude target given a climb rate and dt
This commit is contained in:
parent
772a1acc37
commit
31edd6a72b
|
@ -169,6 +169,14 @@ void AC_PosControl::set_alt_target_from_climb_rate(float climb_rate_cms, float d
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/// add_takeoff_climb_rate - adjusts alt target up or down using a climb rate in cm/s
|
||||||
|
/// should be called continuously (with dt set to be the expected time between calls)
|
||||||
|
/// almost no checks are performed on the input
|
||||||
|
void AC_PosControl::add_takeoff_climb_rate(float climb_rate_cms, float dt)
|
||||||
|
{
|
||||||
|
_pos_target.z += climb_rate_cms * dt;
|
||||||
|
}
|
||||||
|
|
||||||
/// relax_alt_hold_controllers - set all desired and targets to measured
|
/// relax_alt_hold_controllers - set all desired and targets to measured
|
||||||
void AC_PosControl::relax_alt_hold_controllers(float throttle_setting)
|
void AC_PosControl::relax_alt_hold_controllers(float throttle_setting)
|
||||||
{
|
{
|
||||||
|
|
|
@ -127,6 +127,11 @@ public:
|
||||||
/// set force_descend to true during landing to allow target to move low enough to slow the motors
|
/// set force_descend to true during landing to allow target to move low enough to slow the motors
|
||||||
void set_alt_target_from_climb_rate(float climb_rate_cms, float dt, bool force_descend = false);
|
void set_alt_target_from_climb_rate(float climb_rate_cms, float dt, bool force_descend = false);
|
||||||
|
|
||||||
|
/// add_takeoff_climb_rate - adjusts alt target up or down using a climb rate in cm/s
|
||||||
|
/// should be called continuously (with dt set to be the expected time between calls)
|
||||||
|
/// almost no checks are performed on the input
|
||||||
|
void add_takeoff_climb_rate(float climb_rate_cms, float dt);
|
||||||
|
|
||||||
/// set_alt_target_to_current_alt - set altitude target to current altitude
|
/// set_alt_target_to_current_alt - set altitude target to current altitude
|
||||||
void set_alt_target_to_current_alt() { _pos_target.z = _inav.get_altitude(); }
|
void set_alt_target_to_current_alt() { _pos_target.z = _inav.get_altitude(); }
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue