Browse Source

AC_WPNav: method to retrieve current desired pilot accels

master
Peter Barker 8 years ago committed by Randy Mackay
parent
commit
1eca4e128d
  1. 4
      libraries/AC_WPNav/AC_WPNav.h

4
libraries/AC_WPNav/AC_WPNav.h

@ -84,7 +84,9 @@ public: @@ -84,7 +84,9 @@ public:
/// set_pilot_desired_acceleration - sets pilot desired acceleration from roll and pitch stick input
void set_pilot_desired_acceleration(float control_roll, float control_pitch);
/// get_pilot_desired_acceleration - gets pilot desired
/// acceleration, body frame, [forward,right]
Vector2f get_pilot_desired_acceleration() const { return Vector2f(_pilot_accel_fwd_cms, _pilot_accel_rgt_cms); }
/// clear_pilot_desired_acceleration - clear pilot desired acceleration
void clear_pilot_desired_acceleration() { _pilot_accel_fwd_cms = 0.0f; _pilot_accel_rgt_cms = 0.0f; }

Loading…
Cancel
Save