mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
uncrustify libraries/AP_Math/matrix3.cpp
This commit is contained in:
parent
64eaadb332
commit
d6e803fd3c
@ -21,7 +21,7 @@
|
|||||||
|
|
||||||
#define HALF_SQRT_2 0.70710678118654757
|
#define HALF_SQRT_2 0.70710678118654757
|
||||||
|
|
||||||
#define MATRIX_ROTATION_NONE Matrix3f(1, 0, 0, 0, 1, 0, 0 ,0, 1)
|
#define MATRIX_ROTATION_NONE Matrix3f(1, 0, 0, 0, 1, 0, 0,0, 1)
|
||||||
#define MATRIX_ROTATION_YAW_45 Matrix3f(HALF_SQRT_2, -HALF_SQRT_2, 0, HALF_SQRT_2, HALF_SQRT_2, 0, 0, 0, 1)
|
#define MATRIX_ROTATION_YAW_45 Matrix3f(HALF_SQRT_2, -HALF_SQRT_2, 0, HALF_SQRT_2, HALF_SQRT_2, 0, 0, 0, 1)
|
||||||
#define MATRIX_ROTATION_YAW_90 Matrix3f(0, -1, 0, 1, 0, 0, 0, 0, 1)
|
#define MATRIX_ROTATION_YAW_90 Matrix3f(0, -1, 0, 1, 0, 0, 0, 0, 1)
|
||||||
#define MATRIX_ROTATION_YAW_135 Matrix3f(-HALF_SQRT_2, -HALF_SQRT_2, 0, HALF_SQRT_2, -HALF_SQRT_2, 0, 0, 0, 1)
|
#define MATRIX_ROTATION_YAW_135 Matrix3f(-HALF_SQRT_2, -HALF_SQRT_2, 0, HALF_SQRT_2, -HALF_SQRT_2, 0, 0, 0, 1)
|
||||||
@ -45,53 +45,53 @@ void Matrix3<T>::rotation(enum Rotation r)
|
|||||||
switch (r) {
|
switch (r) {
|
||||||
case ROTATION_NONE:
|
case ROTATION_NONE:
|
||||||
case ROTATION_MAX:
|
case ROTATION_MAX:
|
||||||
*this = MATRIX_ROTATION_NONE;
|
*this = MATRIX_ROTATION_NONE;
|
||||||
break;
|
break;
|
||||||
case ROTATION_YAW_45:
|
case ROTATION_YAW_45:
|
||||||
*this = MATRIX_ROTATION_YAW_45;
|
*this = MATRIX_ROTATION_YAW_45;
|
||||||
break;
|
break;
|
||||||
case ROTATION_YAW_90:
|
case ROTATION_YAW_90:
|
||||||
*this = MATRIX_ROTATION_YAW_90;
|
*this = MATRIX_ROTATION_YAW_90;
|
||||||
break;
|
break;
|
||||||
case ROTATION_YAW_135:
|
case ROTATION_YAW_135:
|
||||||
*this = MATRIX_ROTATION_YAW_135;
|
*this = MATRIX_ROTATION_YAW_135;
|
||||||
break;
|
break;
|
||||||
case ROTATION_YAW_180:
|
case ROTATION_YAW_180:
|
||||||
*this = MATRIX_ROTATION_YAW_180;
|
*this = MATRIX_ROTATION_YAW_180;
|
||||||
break;
|
break;
|
||||||
case ROTATION_YAW_225:
|
case ROTATION_YAW_225:
|
||||||
*this = MATRIX_ROTATION_YAW_225;
|
*this = MATRIX_ROTATION_YAW_225;
|
||||||
break;
|
break;
|
||||||
case ROTATION_YAW_270:
|
case ROTATION_YAW_270:
|
||||||
*this = MATRIX_ROTATION_YAW_270;
|
*this = MATRIX_ROTATION_YAW_270;
|
||||||
break;
|
break;
|
||||||
case ROTATION_YAW_315:
|
case ROTATION_YAW_315:
|
||||||
*this = MATRIX_ROTATION_YAW_315;
|
*this = MATRIX_ROTATION_YAW_315;
|
||||||
break;
|
break;
|
||||||
case ROTATION_ROLL_180:
|
case ROTATION_ROLL_180:
|
||||||
*this = MATRIX_ROTATION_ROLL_180;
|
*this = MATRIX_ROTATION_ROLL_180;
|
||||||
break;
|
break;
|
||||||
case ROTATION_ROLL_180_YAW_45:
|
case ROTATION_ROLL_180_YAW_45:
|
||||||
*this = MATRIX_ROTATION_ROLL_180_YAW_45;
|
*this = MATRIX_ROTATION_ROLL_180_YAW_45;
|
||||||
break;
|
break;
|
||||||
case ROTATION_ROLL_180_YAW_90:
|
case ROTATION_ROLL_180_YAW_90:
|
||||||
*this = MATRIX_ROTATION_ROLL_180_YAW_90;
|
*this = MATRIX_ROTATION_ROLL_180_YAW_90;
|
||||||
break;
|
break;
|
||||||
case ROTATION_ROLL_180_YAW_135:
|
case ROTATION_ROLL_180_YAW_135:
|
||||||
*this = MATRIX_ROTATION_ROLL_180_YAW_135;
|
*this = MATRIX_ROTATION_ROLL_180_YAW_135;
|
||||||
break;
|
break;
|
||||||
case ROTATION_PITCH_180:
|
case ROTATION_PITCH_180:
|
||||||
*this = MATRIX_ROTATION_PITCH_180;
|
*this = MATRIX_ROTATION_PITCH_180;
|
||||||
break;
|
break;
|
||||||
case ROTATION_ROLL_180_YAW_225:
|
case ROTATION_ROLL_180_YAW_225:
|
||||||
*this = MATRIX_ROTATION_ROLL_180_YAW_225;
|
*this = MATRIX_ROTATION_ROLL_180_YAW_225;
|
||||||
break;
|
break;
|
||||||
case ROTATION_ROLL_180_YAW_270:
|
case ROTATION_ROLL_180_YAW_270:
|
||||||
*this = MATRIX_ROTATION_ROLL_180_YAW_270;
|
*this = MATRIX_ROTATION_ROLL_180_YAW_270;
|
||||||
break;
|
break;
|
||||||
case ROTATION_ROLL_180_YAW_315:
|
case ROTATION_ROLL_180_YAW_315:
|
||||||
*this = MATRIX_ROTATION_ROLL_180_YAW_315;
|
*this = MATRIX_ROTATION_ROLL_180_YAW_315;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -100,22 +100,22 @@ void Matrix3<T>::rotation(enum Rotation r)
|
|||||||
template <typename T>
|
template <typename T>
|
||||||
void Matrix3<T>::from_euler(float roll, float pitch, float yaw)
|
void Matrix3<T>::from_euler(float roll, float pitch, float yaw)
|
||||||
{
|
{
|
||||||
float cp = cos(pitch);
|
float cp = cos(pitch);
|
||||||
float sp = sin(pitch);
|
float sp = sin(pitch);
|
||||||
float sr = sin(roll);
|
float sr = sin(roll);
|
||||||
float cr = cos(roll);
|
float cr = cos(roll);
|
||||||
float sy = sin(yaw);
|
float sy = sin(yaw);
|
||||||
float cy = cos(yaw);
|
float cy = cos(yaw);
|
||||||
|
|
||||||
a.x = cp * cy;
|
a.x = cp * cy;
|
||||||
a.y = (sr * sp * cy) - (cr * sy);
|
a.y = (sr * sp * cy) - (cr * sy);
|
||||||
a.z = (cr * sp * cy) + (sr * sy);
|
a.z = (cr * sp * cy) + (sr * sy);
|
||||||
b.x = cp * sy;
|
b.x = cp * sy;
|
||||||
b.y = (sr * sp * sy) + (cr * cy);
|
b.y = (sr * sp * sy) + (cr * cy);
|
||||||
b.z = (cr * sp * sy) - (sr * cy);
|
b.z = (cr * sp * sy) - (sr * cy);
|
||||||
c.x = -sp;
|
c.x = -sp;
|
||||||
c.y = sr * cp;
|
c.y = sr * cp;
|
||||||
c.z = cr * cp;
|
c.z = cr * cp;
|
||||||
}
|
}
|
||||||
|
|
||||||
// calculate euler angles from a rotation matrix
|
// calculate euler angles from a rotation matrix
|
||||||
@ -123,15 +123,15 @@ void Matrix3<T>::from_euler(float roll, float pitch, float yaw)
|
|||||||
template <typename T>
|
template <typename T>
|
||||||
void Matrix3<T>::to_euler(float *roll, float *pitch, float *yaw)
|
void Matrix3<T>::to_euler(float *roll, float *pitch, float *yaw)
|
||||||
{
|
{
|
||||||
if (pitch != NULL) {
|
if (pitch != NULL) {
|
||||||
*pitch = -safe_asin(c.x);
|
*pitch = -safe_asin(c.x);
|
||||||
}
|
}
|
||||||
if (roll != NULL) {
|
if (roll != NULL) {
|
||||||
*roll = atan2(c.y, c.z);
|
*roll = atan2(c.y, c.z);
|
||||||
}
|
}
|
||||||
if (yaw != NULL) {
|
if (yaw != NULL) {
|
||||||
*yaw = atan2(b.x, a.x);
|
*yaw = atan2(b.x, a.x);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// apply an additional rotation from a body frame gyro vector
|
// apply an additional rotation from a body frame gyro vector
|
||||||
@ -139,18 +139,18 @@ void Matrix3<T>::to_euler(float *roll, float *pitch, float *yaw)
|
|||||||
template <typename T>
|
template <typename T>
|
||||||
void Matrix3<T>::rotate(const Vector3<T> &g)
|
void Matrix3<T>::rotate(const Vector3<T> &g)
|
||||||
{
|
{
|
||||||
Matrix3f temp_matrix;
|
Matrix3f temp_matrix;
|
||||||
temp_matrix.a.x = a.y * g.z - a.z * g.y;
|
temp_matrix.a.x = a.y * g.z - a.z * g.y;
|
||||||
temp_matrix.a.y = a.z * g.x - a.x * g.z;
|
temp_matrix.a.y = a.z * g.x - a.x * g.z;
|
||||||
temp_matrix.a.z = a.x * g.y - a.y * g.x;
|
temp_matrix.a.z = a.x * g.y - a.y * g.x;
|
||||||
temp_matrix.b.x = b.y * g.z - b.z * g.y;
|
temp_matrix.b.x = b.y * g.z - b.z * g.y;
|
||||||
temp_matrix.b.y = b.z * g.x - b.x * g.z;
|
temp_matrix.b.y = b.z * g.x - b.x * g.z;
|
||||||
temp_matrix.b.z = b.x * g.y - b.y * g.x;
|
temp_matrix.b.z = b.x * g.y - b.y * g.x;
|
||||||
temp_matrix.c.x = c.y * g.z - c.z * g.y;
|
temp_matrix.c.x = c.y * g.z - c.z * g.y;
|
||||||
temp_matrix.c.y = c.z * g.x - c.x * g.z;
|
temp_matrix.c.y = c.z * g.x - c.x * g.z;
|
||||||
temp_matrix.c.z = c.x * g.y - c.y * g.x;
|
temp_matrix.c.z = c.x * g.y - c.y * g.x;
|
||||||
|
|
||||||
(*this) += temp_matrix;
|
(*this) += temp_matrix;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user