mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AC_WPNav: add get_target_alt method
This commit is contained in:
parent
6dbcbdcb43
commit
bc87118062
@ -1967,7 +1967,7 @@ void update_throttle_mode(void)
|
||||
case THROTTLE_AUTO:
|
||||
// auto pilot altitude controller with target altitude held in next_WP.alt
|
||||
if(motors.auto_armed() == true) {
|
||||
get_throttle_althold_with_slew(wp_nav.get_destination_alt(), g.auto_velocity_z_min, g.auto_velocity_z_max);
|
||||
get_throttle_althold_with_slew(wp_nav.get_target_alt(), g.auto_velocity_z_min, g.auto_velocity_z_max);
|
||||
}
|
||||
break;
|
||||
|
||||
|
@ -39,6 +39,9 @@ public:
|
||||
/// get_loiter_target - get loiter target as position vector (from home in cm)
|
||||
Vector3f get_loiter_target() { return _target; }
|
||||
|
||||
/// get_target_alt - get loiter's target altitude
|
||||
float get_target_alt() { return _target.z; }
|
||||
|
||||
/// set_loiter_target in cm from home
|
||||
void set_loiter_target(const Vector3f& position) { _target = position; }
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user