mirror of https://github.com/ArduPilot/ardupilot
AP_Math: Add comments to quaternion methods
This commit is contained in:
parent
1dba013e4a
commit
527b0e5ba9
|
@ -534,6 +534,8 @@ void QuaternionT<T>::from_axis_angle_fast(const Vector3<T> &axis, T theta)
|
|||
q4 = axis.z * st2;
|
||||
}
|
||||
|
||||
// create a quaternion by integrating an angular velocity over some time_delta, which is
|
||||
// assumed to be small
|
||||
template <typename T>
|
||||
void QuaternionT<T>::from_angular_velocity(const Vector3<T>& angular_velocity, float time_delta)
|
||||
{
|
||||
|
|
|
@ -112,6 +112,8 @@ public:
|
|||
// the axis vector must be length 1, theta should less than 0.17 radians (i.e. 10 degrees)
|
||||
void from_axis_angle_fast(const Vector3<T> &axis, T theta);
|
||||
|
||||
// create a quaternion by integrating an angular velocity over some time_delta, which is
|
||||
// assumed to be small
|
||||
void from_angular_velocity(const Vector3<T>& angular_velocity, float time_delta);
|
||||
|
||||
// rotate by the provided rotation vector
|
||||
|
|
Loading…
Reference in New Issue