mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_NavEKF3: fix comments
This commit is contained in:
parent
4640c24872
commit
4b8be2e535
@ -1215,7 +1215,7 @@ void NavEKF3::getRotationBodyToNED(Matrix3f &mat) const
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// return the quaternions defining the rotation from NED to XYZ (body) axes
|
// return the quaternions defining the rotation from XYZ (body) to NED axes
|
||||||
void NavEKF3::getQuaternionBodyToNED(int8_t instance, Quaternion &quat) const
|
void NavEKF3::getQuaternionBodyToNED(int8_t instance, Quaternion &quat) const
|
||||||
{
|
{
|
||||||
if (instance < 0 || instance >= num_cores) instance = primary;
|
if (instance < 0 || instance >= num_cores) instance = primary;
|
||||||
|
@ -179,7 +179,7 @@ public:
|
|||||||
// return the transformation matrix from XYZ (body) to NED axes
|
// return the transformation matrix from XYZ (body) to NED axes
|
||||||
void getRotationBodyToNED(Matrix3f &mat) const;
|
void getRotationBodyToNED(Matrix3f &mat) const;
|
||||||
|
|
||||||
// return the quaternions defining the rotation from NED to XYZ (body) axes
|
// return the quaternions defining the rotation from XYZ (body) to NED axes
|
||||||
void getQuaternionBodyToNED(int8_t instance, Quaternion &quat) const;
|
void getQuaternionBodyToNED(int8_t instance, Quaternion &quat) const;
|
||||||
|
|
||||||
// return the quaternions defining the rotation from NED to XYZ (autopilot) axes
|
// return the quaternions defining the rotation from NED to XYZ (autopilot) axes
|
||||||
|
Loading…
Reference in New Issue
Block a user