mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 06:58:39 -04:00
AC_AttitudeControl: Add AC_PosControl::get_bearing_to_target() method
This commit is contained in:
parent
63639a0838
commit
fa4427fbce
@ -617,12 +617,18 @@ void AC_PosControl::get_stopping_point_xy(Vector3f &stopping_point) const
|
||||
stopping_point.y = curr_pos.y + (stopping_dist * curr_vel.y / vel_total);
|
||||
}
|
||||
|
||||
/// get_distance_to_target - get horizontal distance to loiter target in cm
|
||||
/// get_distance_to_target - get horizontal distance to target position in cm
|
||||
float AC_PosControl::get_distance_to_target() const
|
||||
{
|
||||
return _distance_to_target;
|
||||
}
|
||||
|
||||
/// get_bearing_to_target - get bearing to target position in centi-degrees
|
||||
int32_t AC_PosControl::get_bearing_to_target() const
|
||||
{
|
||||
return get_bearing_cd(_inav.get_position(), _pos_target);
|
||||
}
|
||||
|
||||
// is_active_xy - returns true if the xy position controller has been run very recently
|
||||
bool AC_PosControl::is_active_xy() const
|
||||
{
|
||||
|
@ -262,6 +262,9 @@ public:
|
||||
/// get_distance_to_target - get horizontal distance to position target in cm (used for reporting)
|
||||
float get_distance_to_target() const;
|
||||
|
||||
/// get_bearing_to_target - get bearing to target position in centi-degrees
|
||||
int32_t get_bearing_to_target() const;
|
||||
|
||||
/// xyz velocity controller
|
||||
|
||||
/// init_vel_controller_xyz - initialise the velocity controller - should be called once before the caller attempts to use the controller
|
||||
|
Loading…
Reference in New Issue
Block a user