mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
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:
parent
02cfbb25b0
commit
ba3325ffd3
@ -140,7 +140,7 @@ static void test_eulers(void)
|
|||||||
test_euler(ROTATION_ROLL_270_PITCH_270,270,270, 0);
|
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_PITCH_180_YAW_90, 90, 180, 90);
|
||||||
test_euler(ROTATION_ROLL_90_YAW_270, 90, 0, 270);
|
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)
|
static bool have_rotation(const Matrix3f &m)
|
||||||
|
@ -64,7 +64,7 @@ enum Rotation {
|
|||||||
ROTATION_ROLL_270_PITCH_270 = 35,
|
ROTATION_ROLL_270_PITCH_270 = 35,
|
||||||
ROTATION_ROLL_90_PITCH_180_YAW_90 = 36,
|
ROTATION_ROLL_90_PITCH_180_YAW_90 = 36,
|
||||||
ROTATION_ROLL_90_YAW_270 = 37,
|
ROTATION_ROLL_90_YAW_270 = 37,
|
||||||
ROTATION_YAW_293_PITCH_68_ROLL_90 = 38,
|
ROTATION_ROLL_90_PITCH_68_YAW_293 = 38,
|
||||||
ROTATION_MAX
|
ROTATION_MAX
|
||||||
};
|
};
|
||||||
/*
|
/*
|
||||||
|
@ -53,7 +53,7 @@ TEST(VectorTest, Rotations)
|
|||||||
TEST_ROTATION(ROTATION_ROLL_270_PITCH_270, 1, 1, 1);
|
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_PITCH_180_YAW_90, 1, -1, -1);
|
||||||
TEST_ROTATION(ROTATION_ROLL_90_YAW_270, -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";
|
EXPECT_EQ(ROTATION_MAX, rotation_count) << "All rotations are expect to be tested";
|
||||||
}
|
}
|
||||||
|
@ -223,7 +223,7 @@ void Vector3<T>::rotate(enum Rotation rotation)
|
|||||||
tmp = x; x = y; y = -tmp;
|
tmp = x; x = y; y = -tmp;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
case ROTATION_YAW_293_PITCH_68_ROLL_90: {
|
case ROTATION_ROLL_90_PITCH_68_YAW_293: {
|
||||||
float tmpx = x;
|
float tmpx = x;
|
||||||
float tmpy = y;
|
float tmpy = y;
|
||||||
float tmpz = z;
|
float tmpz = z;
|
||||||
|
Loading…
Reference in New Issue
Block a user