AP_Math: add custom rotation option

This commit is contained in:
Jacob Walser 2018-03-08 21:17:29 -05:00 committed by Francisco Ferreira
parent 4f02f709a2
commit f97ac4af30
2 changed files with 5 additions and 2 deletions

View File

@ -66,11 +66,12 @@ enum Rotation : uint8_t {
ROTATION_ROLL_90_PITCH_68_YAW_293 = 38, ROTATION_ROLL_90_PITCH_68_YAW_293 = 38,
ROTATION_PITCH_315 = 39, ROTATION_PITCH_315 = 39,
ROTATION_ROLL_90_PITCH_315 = 40, ROTATION_ROLL_90_PITCH_315 = 40,
ROTATION_MAX ROTATION_MAX,
ROTATION_CUSTOM = 100,
}; };
/* /*
Here are the same values in a form sutable for a @Values attribute in Here are the same values in a form sutable for a @Values attribute in
auto documentation: 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:Roll270Yaw135,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 @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:Roll270Yaw135,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,100:Custom
*/ */

View File

@ -244,6 +244,8 @@ void Vector3<T>::rotate(enum Rotation rotation)
x = tmp; x = tmp;
return; return;
} }
case ROTATION_CUSTOM: // no-op; caller should perform custom rotations via matrix multiplication
return;
} }
} }