Go to the documentation of this file. 5 #define MOT_1_ROLL_FACTOR 0.0 6 #define MOT_1_PITCH_FACTOR 0.0 7 #define MOT_1_YAW_FACTOR 1.0 8 #define MOT_1_THROTTLE_FACTOR 0.0 9 #define MOT_1_FORWARD_FACTOR -1 10 #define MOT_1_STRAFE_FACTOR 1 13 #define MOT_2_ROLL_FACTOR 0.0 14 #define MOT_2_PITCH_FACTOR 0.0 15 #define MOT_2_YAW_FACTOR -1.0 16 #define MOT_2_THROTTLE_FACTOR 0.0 17 #define MOT_2_FORWARD_FACTOR -1 18 #define MOT_2_STRAFE_FACTOR -1 21 #define MOT_3_ROLL_FACTOR 0 22 #define MOT_3_PITCH_FACTOR 0 23 #define MOT_3_YAW_FACTOR -1.0 24 #define MOT_3_THROTTLE_FACTOR 0.0 25 #define MOT_3_FORWARD_FACTOR 1 26 #define MOT_3_STRAFE_FACTOR 1 29 #define MOT_4_ROLL_FACTOR 0 30 #define MOT_4_PITCH_FACTOR 0 31 #define MOT_4_YAW_FACTOR 1.0 32 #define MOT_4_THROTTLE_FACTOR 0.0 33 #define MOT_4_FORWARD_FACTOR 1 34 #define MOT_4_STRAFE_FACTOR -1 37 #define MOT_5_ROLL_FACTOR 1.0 38 #define MOT_5_PITCH_FACTOR 0.0 39 #define MOT_5_YAW_FACTOR 0.0 40 #define MOT_5_THROTTLE_FACTOR -1 41 #define MOT_5_FORWARD_FACTOR 0.0 42 #define MOT_5_STRAFE_FACTOR 0.0 45 #define MOT_6_ROLL_FACTOR -1.0 46 #define MOT_6_PITCH_FACTOR 0.0 47 #define MOT_6_YAW_FACTOR 0.0 48 #define MOT_6_THROTTLE_FACTOR -1 49 #define MOT_6_FORWARD_FACTOR 0.0 50 #define MOT_6_STRAFE_FACTOR 0.0