@ -108,6 +108,9 @@ public:
@@ -108,6 +108,9 @@ public:
/// target will also be stopped if the motors hit their limits or leash length is exceeded
void set_alt_target_from_climb_rate ( float climb_rate_cms , float dt ) ;
/// 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 ( ) ; }
/// get_alt_target, get_desired_alt - get desired altitude (in cm above home) from loiter or wp controller which should be fed into throttle controller
/// To-Do: remove one of the two functions below
float get_alt_target ( ) const { return _pos_target . z ; }