mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Math: updated EulerAngles.pdf link
This commit is contained in:
parent
98733882f5
commit
2ce6532698
@ -21,7 +21,7 @@
|
|||||||
#include "AP_Math.h"
|
#include "AP_Math.h"
|
||||||
|
|
||||||
// create a rotation matrix given some euler angles
|
// create a rotation matrix given some euler angles
|
||||||
// this is based on http://gentlenav.googlecode.com/files/EulerAngles.pdf
|
// this is based on https://github.com/ArduPilot/Datasheets/blob/main/References/EulerAngles.pdf
|
||||||
template <typename T>
|
template <typename T>
|
||||||
void Matrix3<T>::from_euler(T roll, T pitch, T yaw)
|
void Matrix3<T>::from_euler(T roll, T pitch, T yaw)
|
||||||
{
|
{
|
||||||
@ -44,7 +44,7 @@ void Matrix3<T>::from_euler(T roll, T pitch, T yaw)
|
|||||||
}
|
}
|
||||||
|
|
||||||
// calculate euler angles from a rotation matrix
|
// calculate euler angles from a rotation matrix
|
||||||
// this is based on http://gentlenav.googlecode.com/files/EulerAngles.pdf
|
// this is based on https://github.com/ArduPilot/Datasheets/blob/main/References/EulerAngles.pdf
|
||||||
template <typename T>
|
template <typename T>
|
||||||
void Matrix3<T>::to_euler(T *roll, T *pitch, T *yaw) const
|
void Matrix3<T>::to_euler(T *roll, T *pitch, T *yaw) const
|
||||||
{
|
{
|
||||||
|
@ -236,7 +236,7 @@ public:
|
|||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
create a rotation matrix from Euler angles in 321 euler orderin
|
create a rotation matrix from Euler angles in 321 euler ordering
|
||||||
*/
|
*/
|
||||||
void from_euler(T roll, T pitch, T yaw);
|
void from_euler(T roll, T pitch, T yaw);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user