AP_Math: rename rotation

The rotations are supposed to follow the name of the enum, in order. The
ROTATION_YAW_293_PITCH_68_ROLL_90 was added with the name of an
intrinsic 321 rotation, but the matrix is actually a 123 rotation,
following the other rotations already present.

Change the name to follow the other names.
This commit is contained in:
Lucas De Marchi 2015-12-28 16:23:18 -02:00
parent 02cfbb25b0
commit ba3325ffd3
4 changed files with 4 additions and 4 deletions

View File

@ -140,7 +140,7 @@ static void test_eulers(void)
test_euler(ROTATION_ROLL_270_PITCH_270,270,270, 0);
test_euler(ROTATION_ROLL_90_PITCH_180_YAW_90, 90, 180, 90);
test_euler(ROTATION_ROLL_90_YAW_270, 90, 0, 270);
test_euler(ROTATION_YAW_293_PITCH_68_ROLL_90,90,68.8,293.3);
test_euler(ROTATION_ROLL_90_PITCH_68_YAW_293,90,68.8,293.3);
}
static bool have_rotation(const Matrix3f &m)

View File

@ -64,7 +64,7 @@ enum Rotation {
ROTATION_ROLL_270_PITCH_270 = 35,
ROTATION_ROLL_90_PITCH_180_YAW_90 = 36,
ROTATION_ROLL_90_YAW_270 = 37,
ROTATION_YAW_293_PITCH_68_ROLL_90 = 38,
ROTATION_ROLL_90_PITCH_68_YAW_293 = 38,
ROTATION_MAX
};
/*

View File

@ -53,7 +53,7 @@ TEST(VectorTest, Rotations)
TEST_ROTATION(ROTATION_ROLL_270_PITCH_270, 1, 1, 1);
TEST_ROTATION(ROTATION_ROLL_90_PITCH_180_YAW_90, 1, -1, -1);
TEST_ROTATION(ROTATION_ROLL_90_YAW_270, -1, -1, 1);
TEST_ROTATION(ROTATION_YAW_293_PITCH_68_ROLL_90, -0.4118548f, -1.58903555f, -0.55257726f);
TEST_ROTATION(ROTATION_ROLL_90_PITCH_68_YAW_293, -0.4118548f, -1.58903555f, -0.55257726f);
EXPECT_EQ(ROTATION_MAX, rotation_count) << "All rotations are expect to be tested";
}

View File

@ -223,7 +223,7 @@ void Vector3<T>::rotate(enum Rotation rotation)
tmp = x; x = y; y = -tmp;
return;
}
case ROTATION_YAW_293_PITCH_68_ROLL_90: {
case ROTATION_ROLL_90_PITCH_68_YAW_293: {
float tmpx = x;
float tmpy = y;
float tmpz = z;