From fab8604f168c64e96fa653fc429341061b9660be Mon Sep 17 00:00:00 2001 From: Robert Lefebvre Date: Wed, 25 Mar 2015 13:58:46 -0400 Subject: [PATCH] Copter: Change Auto Yaw #define table into Enum. --- ArduCopter/defines.h | 17 +++++++++-------- 1 file changed, 9 insertions(+), 8 deletions(-) diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index 42ed2893eb..01f1b1af10 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -13,14 +13,15 @@ #define ENABLE ENABLED #define DISABLE DISABLED -// Flight modes -// ------------ -#define AUTO_YAW_HOLD 0 // pilot controls the heading -#define AUTO_YAW_LOOK_AT_NEXT_WP 1 // point towards next waypoint (no pilot input accepted) -#define AUTO_YAW_ROI 2 // point towards a location held in roi_WP (no pilot input accepted) -#define AUTO_YAW_LOOK_AT_HEADING 3 // point towards a particular angle (not pilot input accepted) -#define AUTO_YAW_LOOK_AHEAD 4 // point in the direction the copter is moving -#define AUTO_YAW_RESETTOARMEDYAW 5 // point towards heading at time motors were armed +// Autopilot Yaw Mode enumeration +enum autopilot_yaw_mode { + AUTO_YAW_HOLD = 0, // pilot controls the heading + AUTO_YAW_LOOK_AT_NEXT_WP = 1, // point towards next waypoint (no pilot input accepted) + AUTO_YAW_ROI = 2, // point towards a location held in roi_WP (no pilot input accepted) + AUTO_YAW_LOOK_AT_HEADING = 3, // point towards a particular angle (not pilot input accepted) + AUTO_YAW_LOOK_AHEAD = 4, // point in the direction the copter is moving + AUTO_YAW_RESETTOARMEDYAW = 5, // point towards heading at time motors were armed +}; // Ch6... Ch12 aux switch control #define AUX_SWITCH_PWM_TRIGGER_HIGH 1800 // pwm value above which the ch7 or ch8 option will be invoked