mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
AP_NavEKF3: use quat.to_euler(Vector3f&)
This commit is contained in:
parent
a3c5926040
commit
ce8afaf57b
@ -88,7 +88,7 @@ bool NavEKF3_core::getHeightControlLimit(float &height) const
|
||||
// return the Euler roll, pitch and yaw angle in radians
|
||||
void NavEKF3_core::getEulerAngles(Vector3f &euler) const
|
||||
{
|
||||
outputDataNew.quat.to_euler(euler.x, euler.y, euler.z);
|
||||
outputDataNew.quat.to_euler(euler);
|
||||
euler = euler - dal.get_trim();
|
||||
}
|
||||
|
||||
|
@ -2064,7 +2064,7 @@ void NavEKF3_core::setYawFromMag()
|
||||
Matrix3F Tbn_zeroYaw;
|
||||
if (order == rotationOrder::TAIT_BRYAN_321) {
|
||||
// rolled more than pitched so use 321 rotation order
|
||||
stateStruct.quat.to_euler(eulerAngles.x, eulerAngles.y, eulerAngles.z);
|
||||
stateStruct.quat.to_euler(eulerAngles);
|
||||
Tbn_zeroYaw.from_euler(eulerAngles.x, eulerAngles.y, 0.0f);
|
||||
} else if (order == rotationOrder::TAIT_BRYAN_312) {
|
||||
// pitched more than rolled so use 312 rotation order
|
||||
|
Loading…
Reference in New Issue
Block a user