Browse Source

AC_WPNav: call renamed functions in AC_AttitudeControl

mission-4.1.18
Jonathan Challinger 9 years ago committed by Randy Mackay
parent
commit
3c4d226b64
  1. 4
      libraries/AC_WPNav/AC_WPNav.cpp

4
libraries/AC_WPNav/AC_WPNav.cpp

@ -464,7 +464,7 @@ void AC_WPNav::set_wp_origin_and_destination(const Vector3f& origin, const Vecto @@ -464,7 +464,7 @@ void AC_WPNav::set_wp_origin_and_destination(const Vector3f& origin, const Vecto
_yaw = get_bearing_cd(_origin, _destination);
} else {
// set target yaw to current heading. Alternatively we could pull this from the attitude controller if we had access to it
_yaw = _attitude_control.angle_ef_targets().z;
_yaw = _attitude_control.get_att_target_euler_cd().z;
}
// initialise intermediate point to the origin
@ -859,7 +859,7 @@ void AC_WPNav::set_spline_origin_and_destination(const Vector3f& origin, const V @@ -859,7 +859,7 @@ void AC_WPNav::set_spline_origin_and_destination(const Vector3f& origin, const V
}
// initialise yaw heading to current heading
_yaw = _attitude_control.angle_ef_targets().z;
_yaw = _attitude_control.get_att_target_euler_cd().z;
// store origin and destination locations
_origin = origin;

Loading…
Cancel
Save