mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AC_WPNav: call renamed functions in AC_AttitudeControl
This commit is contained in:
parent
709fcf37cc
commit
3c4d226b64
@ -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
|
||||
}
|
||||
|
||||
// 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…
Reference in New Issue
Block a user