Browse Source

AC_WPNav: use atan2f, make methods const

master
Randy Mackay 11 years ago
parent
commit
b15d4379d8
  1. 6
      libraries/AC_WPNav/AC_WPNav.cpp
  2. 6
      libraries/AC_WPNav/AC_WPNav.h

6
libraries/AC_WPNav/AC_WPNav.cpp

@ -424,7 +424,7 @@ void AC_WPNav::advance_wp_target_along_track(float dt) @@ -424,7 +424,7 @@ void AC_WPNav::advance_wp_target_along_track(float dt)
}
/// get_wp_distance_to_destination - get horizontal distance to destination in cm
float AC_WPNav::get_wp_distance_to_destination()
float AC_WPNav::get_wp_distance_to_destination() const
{
// get current location
Vector3f curr = _inav->get_position();
@ -432,7 +432,7 @@ float AC_WPNav::get_wp_distance_to_destination() @@ -432,7 +432,7 @@ float AC_WPNav::get_wp_distance_to_destination()
}
/// get_wp_bearing_to_destination - get bearing to next waypoint in centi-degrees
int32_t AC_WPNav::get_wp_bearing_to_destination()
int32_t AC_WPNav::get_wp_bearing_to_destination() const
{
return get_bearing_cd(_inav->get_position(), _destination);
}
@ -709,7 +709,7 @@ void AC_WPNav::advance_spline_target_along_track(float dt) @@ -709,7 +709,7 @@ void AC_WPNav::advance_spline_target_along_track(float dt)
_pos_control.set_pos_target(target_pos);
// update the yaw
_yaw = RadiansToCentiDegrees(atan2(target_vel.y,target_vel.x));
_yaw = RadiansToCentiDegrees(atan2f(target_vel.y,target_vel.x));
// advance spline time to next step
_spline_time += spline_time_scale*dt;

6
libraries/AC_WPNav/AC_WPNav.h

@ -114,10 +114,10 @@ public: @@ -114,10 +114,10 @@ public:
void get_wp_stopping_point_xy(Vector3f& stopping_point) const;
/// get_wp_distance_to_destination - get horizontal distance to destination in cm
float get_wp_distance_to_destination();
float get_wp_distance_to_destination() const;
/// get_bearing_to_destination - get bearing to next waypoint in centi-degrees
int32_t get_wp_bearing_to_destination();
int32_t get_wp_bearing_to_destination() const;
/// reached_destination - true when we have come within RADIUS cm of the waypoint
bool reached_wp_destination() const { return _flags.reached_destination; }
@ -147,7 +147,7 @@ public: @@ -147,7 +147,7 @@ public:
// spline-fast - next segment is spline, vehicle's destination velocity should be parallel to position difference vector from previous segment's origin to this segment's destination
// get_yaw - returns target yaw in centi-degrees (used for wp and spline navigation)
float get_yaw() { return _yaw; }
float get_yaw() const { return _yaw; }
/// set_spline_destination waypoint using position vector (distance from home in cm)
/// stopped_at_start should be set to true if vehicle is stopped at the origin

Loading…
Cancel
Save