mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-19 09:09:05 +08:00
254 lines
5.5 KiB
C++
254 lines
5.5 KiB
C++
/****************************************************************************
|
|
*
|
|
* Copyright (C) 2013 PX4 Development Team. All rights reserved.
|
|
*
|
|
* Redistribution and use in source and binary forms, with or without
|
|
* modification, are permitted provided that the following conditions
|
|
* are met:
|
|
*
|
|
* 1. Redistributions of source code must retain the above copyright
|
|
* notice, this list of conditions and the following disclaimer.
|
|
* 2. Redistributions in binary form must reproduce the above copyright
|
|
* notice, this list of conditions and the following disclaimer in
|
|
* the documentation and/or other materials provided with the
|
|
* distribution.
|
|
* 3. Neither the name PX4 nor the names of its contributors may be
|
|
* used to endorse or promote products derived from this software
|
|
* without specific prior written permission.
|
|
*
|
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
|
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
|
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
|
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
|
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
|
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
|
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
|
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
|
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
|
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
|
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
|
* POSSIBILITY OF SUCH DAMAGE.
|
|
*
|
|
****************************************************************************/
|
|
|
|
/**
|
|
* @file rotation.cpp
|
|
*
|
|
* Vector rotation library
|
|
*/
|
|
|
|
#include "math.h"
|
|
#include "rotation.h"
|
|
|
|
__EXPORT void
|
|
get_rot_matrix(enum Rotation rot, math::Matrix<3, 3> *rot_matrix)
|
|
{
|
|
float roll = M_DEG_TO_RAD_F * (float)rot_lookup[rot].roll;
|
|
float pitch = M_DEG_TO_RAD_F * (float)rot_lookup[rot].pitch;
|
|
float yaw = M_DEG_TO_RAD_F * (float)rot_lookup[rot].yaw;
|
|
|
|
rot_matrix->from_euler(roll, pitch, yaw);
|
|
}
|
|
|
|
#define HALF_SQRT_2 0.70710678118654757f
|
|
|
|
__EXPORT void
|
|
rotate_3f(enum Rotation rot, float &x, float &y, float &z)
|
|
{
|
|
float tmp;
|
|
|
|
switch (rot) {
|
|
case ROTATION_NONE:
|
|
case ROTATION_MAX:
|
|
return;
|
|
|
|
case ROTATION_YAW_45: {
|
|
tmp = HALF_SQRT_2 * (x - y);
|
|
y = HALF_SQRT_2 * (x + y);
|
|
x = tmp;
|
|
return;
|
|
}
|
|
|
|
case ROTATION_YAW_90: {
|
|
tmp = x; x = -y; y = tmp;
|
|
return;
|
|
}
|
|
|
|
case ROTATION_YAW_135: {
|
|
tmp = -HALF_SQRT_2 * (x + y);
|
|
y = HALF_SQRT_2 * (x - y);
|
|
x = tmp;
|
|
return;
|
|
}
|
|
|
|
case ROTATION_YAW_180:
|
|
x = -x; y = -y;
|
|
return;
|
|
|
|
case ROTATION_YAW_225: {
|
|
tmp = HALF_SQRT_2 * (y - x);
|
|
y = -HALF_SQRT_2 * (x + y);
|
|
x = tmp;
|
|
return;
|
|
}
|
|
|
|
case ROTATION_YAW_270: {
|
|
tmp = x; x = y; y = -tmp;
|
|
return;
|
|
}
|
|
|
|
case ROTATION_YAW_315: {
|
|
tmp = HALF_SQRT_2 * (x + y);
|
|
y = HALF_SQRT_2 * (y - x);
|
|
x = tmp;
|
|
return;
|
|
}
|
|
|
|
case ROTATION_ROLL_180: {
|
|
y = -y; z = -z;
|
|
return;
|
|
}
|
|
|
|
case ROTATION_ROLL_180_YAW_45: {
|
|
tmp = HALF_SQRT_2 * (x + y);
|
|
y = HALF_SQRT_2 * (x - y);
|
|
x = tmp; z = -z;
|
|
return;
|
|
}
|
|
|
|
case ROTATION_ROLL_180_YAW_90: {
|
|
tmp = x; x = y; y = tmp; z = -z;
|
|
return;
|
|
}
|
|
|
|
case ROTATION_ROLL_180_YAW_135: {
|
|
tmp = HALF_SQRT_2 * (y - x);
|
|
y = HALF_SQRT_2 * (y + x);
|
|
x = tmp; z = -z;
|
|
return;
|
|
}
|
|
|
|
case ROTATION_PITCH_180: {
|
|
x = -x; z = -z;
|
|
return;
|
|
}
|
|
|
|
case ROTATION_ROLL_180_YAW_225: {
|
|
tmp = -HALF_SQRT_2 * (x + y);
|
|
y = HALF_SQRT_2 * (y - x);
|
|
x = tmp; z = -z;
|
|
return;
|
|
}
|
|
|
|
case ROTATION_ROLL_180_YAW_270: {
|
|
tmp = x; x = -y; y = -tmp; z = -z;
|
|
return;
|
|
}
|
|
|
|
case ROTATION_ROLL_180_YAW_315: {
|
|
tmp = HALF_SQRT_2 * (x - y);
|
|
y = -HALF_SQRT_2 * (x + y);
|
|
x = tmp; z = -z;
|
|
return;
|
|
}
|
|
|
|
case ROTATION_ROLL_90: {
|
|
tmp = z; z = y; y = -tmp;
|
|
return;
|
|
}
|
|
|
|
case ROTATION_ROLL_90_YAW_45: {
|
|
tmp = z; z = y; y = -tmp;
|
|
tmp = HALF_SQRT_2 * (x - y);
|
|
y = HALF_SQRT_2 * (x + y);
|
|
x = tmp;
|
|
return;
|
|
}
|
|
|
|
case ROTATION_ROLL_90_YAW_90: {
|
|
tmp = z; z = y; y = -tmp;
|
|
tmp = x; x = -y; y = tmp;
|
|
return;
|
|
}
|
|
|
|
case ROTATION_ROLL_90_YAW_135: {
|
|
tmp = z; z = y; y = -tmp;
|
|
tmp = -HALF_SQRT_2 * (x + y);
|
|
y = HALF_SQRT_2 * (x - y);
|
|
x = tmp;
|
|
return;
|
|
}
|
|
|
|
case ROTATION_ROLL_270: {
|
|
tmp = z; z = -y; y = tmp;
|
|
return;
|
|
}
|
|
|
|
case ROTATION_ROLL_270_YAW_45: {
|
|
tmp = z; z = -y; y = tmp;
|
|
tmp = HALF_SQRT_2 * (x - y);
|
|
y = HALF_SQRT_2 * (x + y);
|
|
x = tmp;
|
|
return;
|
|
}
|
|
|
|
case ROTATION_ROLL_270_YAW_90: {
|
|
tmp = z; z = -y; y = tmp;
|
|
tmp = x; x = -y; y = tmp;
|
|
return;
|
|
}
|
|
|
|
case ROTATION_ROLL_270_YAW_135: {
|
|
tmp = z; z = -y; y = tmp;
|
|
tmp = -HALF_SQRT_2 * (x + y);
|
|
y = HALF_SQRT_2 * (x - y);
|
|
x = tmp;
|
|
return;
|
|
}
|
|
|
|
case ROTATION_ROLL_270_YAW_270: {
|
|
tmp = z; z = -y; y = tmp;
|
|
tmp = x; x = y; y = -tmp;
|
|
return;
|
|
}
|
|
|
|
case ROTATION_PITCH_90: {
|
|
tmp = z; z = -x; x = tmp;
|
|
return;
|
|
}
|
|
|
|
case ROTATION_PITCH_270: {
|
|
tmp = z; z = x; x = -tmp;
|
|
return;
|
|
}
|
|
|
|
case ROTATION_ROLL_180_PITCH_270: {
|
|
tmp = z; z = x; x = tmp;
|
|
y = -y;
|
|
return;
|
|
}
|
|
|
|
case ROTATION_PITCH_90_YAW_180: {
|
|
tmp = x; x = z; z = tmp;
|
|
y = -y;
|
|
return;
|
|
}
|
|
|
|
case ROTATION_PITCH_90_ROLL_90: {
|
|
tmp = x; x = y;
|
|
y = -z; z = -tmp;
|
|
return;
|
|
}
|
|
|
|
case ROTATION_YAW_293_PITCH_68_ROLL_90: {
|
|
float tmpx = x;
|
|
float tmpy = y;
|
|
float tmpz = z;
|
|
x = 0.143039f * tmpx + 0.368776f * tmpy + -0.918446f * tmpz;
|
|
y = -0.332133f * tmpx + -0.856289f * tmpy + -0.395546f * tmpz;
|
|
z = -0.932324f * tmpx + 0.361625f * tmpy + 0.000000f * tmpz;
|
|
return;
|
|
}
|
|
}
|
|
}
|