AP_Math: Add ROTATION_PITCH_315 and ROTATION_ROLL_90_PITCH_315

This commit is contained in:
Jacob Walser 2018-03-08 18:08:18 -05:00 committed by Francisco Ferreira
parent 2aceab2b66
commit e738f33770
3 changed files with 18 additions and 1 deletions

View File

@ -64,11 +64,13 @@ enum Rotation : uint8_t {
ROTATION_ROLL_90_PITCH_180_YAW_90 = 36,
ROTATION_ROLL_90_YAW_270 = 37,
ROTATION_ROLL_90_PITCH_68_YAW_293 = 38,
ROTATION_PITCH_315 = 39,
ROTATION_ROLL_90_PITCH_315 = 40,
ROTATION_MAX
};
/*
Here are the same values in a form sutable for a @Values attribute in
auto documentation:
@Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Roll180Yaw45,10:Roll180Yaw90,11:Roll180Yaw135,12:Pitch180,13:Roll180Yaw225,14:Roll180Yaw270,15:Roll180Yaw315,16:Roll90,17:Roll90Yaw45,18:Roll90Yaw90,19:Roll90Yaw135,20:Roll270,21:Roll270Yaw45,22:Roll270Yaw90,23:Roll270Yaw136,24:Pitch90,25:Pitch270,26:Pitch180Yaw90,27:Pitch180Yaw270,28:Roll90Pitch90,29:Roll180Pitch90,30:Roll270Pitch90,31:Roll90Pitch180,32:Roll270Pitch180,33:Roll90Pitch270,34:Roll180Pitch270,35:Roll270Pitch270,36:Roll90Pitch180Yaw90,37:Roll90Yaw270,38:Yaw293Pitch68Roll180
@Values: 0:None,1:Yaw45,2:Yaw90,3:Yaw135,4:Yaw180,5:Yaw225,6:Yaw270,7:Yaw315,8:Roll180,9:Roll180Yaw45,10:Roll180Yaw90,11:Roll180Yaw135,12:Pitch180,13:Roll180Yaw225,14:Roll180Yaw270,15:Roll180Yaw315,16:Roll90,17:Roll90Yaw45,18:Roll90Yaw90,19:Roll90Yaw135,20:Roll270,21:Roll270Yaw45,22:Roll270Yaw90,23:Roll270Yaw136,24:Pitch90,25:Pitch270,26:Pitch180Yaw90,27:Pitch180Yaw270,28:Roll90Pitch90,29:Roll180Pitch90,30:Roll270Pitch90,31:Roll90Pitch180,32:Roll270Pitch180,33:Roll90Pitch270,34:Roll180Pitch270,35:Roll270Pitch270,36:Roll90Pitch180Yaw90,37:Roll90Yaw270,38:Yaw293Pitch68Roll180,39:Pitch315,40:Roll90Pitch315
*/

View File

@ -59,6 +59,8 @@ TEST(VectorTest, Rotations)
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_PITCH_68_YAW_293, -0.4066309f, -1.5839677f, -0.5706992f);
TEST_ROTATION(ROTATION_PITCH_315, 0, 1, SQRT_2);
TEST_ROTATION(ROTATION_ROLL_90_PITCH_315, 0, -1, SQRT_2);
EXPECT_EQ(ROTATION_MAX, rotation_count) << "All rotations are expect to be tested";
}

View File

@ -231,6 +231,19 @@ void Vector3<T>::rotate(enum Rotation rotation)
z = -0.932324f * tmpx + 0.361625f * tmpy + 0.000000f * tmpz;
return;
}
case ROTATION_PITCH_315: {
tmp = HALF_SQRT_2*(float)(x - z);
z = HALF_SQRT_2*(float)(x + z);
x = tmp;
return;
}
case ROTATION_ROLL_90_PITCH_315: {
tmp = z; z = y; y = -tmp;
tmp = HALF_SQRT_2*(float)(x - z);
z = HALF_SQRT_2*(float)(x + z);
x = tmp;
return;
}
}
}