AP_Math: Add comments to quaternion methods

This commit is contained in:
MatthewHampsey 2022-09-22 15:56:49 +10:00 committed by Andrew Tridgell
parent 1dba013e4a
commit 527b0e5ba9
2 changed files with 4 additions and 0 deletions

View File

@ -534,6 +534,8 @@ void QuaternionT<T>::from_axis_angle_fast(const Vector3<T> &axis, T theta)
q4 = axis.z * st2; 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> template <typename T>
void QuaternionT<T>::from_angular_velocity(const Vector3<T>& angular_velocity, float time_delta) void QuaternionT<T>::from_angular_velocity(const Vector3<T>& angular_velocity, float time_delta)
{ {

View File

@ -112,6 +112,8 @@ public:
// the axis vector must be length 1, theta should less than 0.17 radians (i.e. 10 degrees) // 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); 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); void from_angular_velocity(const Vector3<T>& angular_velocity, float time_delta);
// rotate by the provided rotation vector // rotate by the provided rotation vector