Browse Source

AC_PosControl: add get_horizontal_error

mission-4.1.18
Jonathan Challinger 9 years ago committed by Randy Mackay
parent
commit
630e5378da
  1. 5
      libraries/AC_AttitudeControl/AC_PosControl.cpp
  2. 3
      libraries/AC_AttitudeControl/AC_PosControl.h

5
libraries/AC_AttitudeControl/AC_PosControl.cpp

@ -744,6 +744,11 @@ void AC_PosControl::update_vel_controller_xyz(float ekfNavVelGainScaler) @@ -744,6 +744,11 @@ void AC_PosControl::update_vel_controller_xyz(float ekfNavVelGainScaler)
update_z_controller();
}
float AC_PosControl::get_horizontal_error() const
{
return norm(_pos_error.x, _pos_error.y);
}
///
/// private methods
///

3
libraries/AC_AttitudeControl/AC_PosControl.h

@ -148,6 +148,9 @@ public: @@ -148,6 +148,9 @@ public:
/// get_alt_error - returns altitude error in cm
float get_alt_error() const;
// returns horizontal error in cm
float get_horizontal_error() const;
/// set_target_to_stopping_point_z - sets altitude target to reasonable stopping altitude in cm above home
void set_target_to_stopping_point_z();

Loading…
Cancel
Save