diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index 1149263298..f30bff7e48 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -33,6 +33,7 @@ //#define MODE_BRAKE_ENABLED DISABLED // disable brake mode support //#define MODE_CIRCLE_ENABLED DISABLED // disable circle mode support //#define MODE_DRIFT_ENABLED DISABLED // disable drift mode support +//#define MODE_FLIP_ENABLED DISABLED // disable flip mode support //#define MODE_FOLLOW_ENABLED DISABLED // disable follow mode support //#define MODE_GUIDED_ENABLED DISABLED // disable guided mode support //#define MODE_GUIDED_NOGPS_ENABLED DISABLED // disable guided/nogps mode support diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 557d5208c6..4ef6370920 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -924,7 +924,9 @@ private: #if MODE_DRIFT_ENABLED == ENABLED ModeDrift mode_drift; #endif +#if MODE_FLIP_ENABLED == ENABLED ModeFlip mode_flip; +#endif #if MODE_FOLLOW_ENABLED == ENABLED ModeFollow mode_follow; #endif diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 08c91bcb94..448e78d342 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -295,6 +295,12 @@ # define MODE_DRIFT_ENABLED ENABLED #endif +////////////////////////////////////////////////////////////////////////////// +// flip - fly vehicle in flip in pitch and roll direction mode +#ifndef MODE_FLIP_ENABLED +# define MODE_FLIP_ENABLED ENABLED +#endif + ////////////////////////////////////////////////////////////////////////////// // Follow - follow another vehicle or GCS #ifndef MODE_FOLLOW_ENABLED diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index 185f05630a..be8473f472 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -97,9 +97,11 @@ Copter::Mode *Copter::mode_from_mode_num(const uint8_t mode) break; #endif +#if MODE_FLIP_ENABLED == ENABLED case FLIP: ret = &mode_flip; break; +#endif #if AUTOTUNE_ENABLED == ENABLED case AUTOTUNE: diff --git a/ArduCopter/mode_flip.cpp b/ArduCopter/mode_flip.cpp index 5e357a225b..f1fe0295e5 100644 --- a/ArduCopter/mode_flip.cpp +++ b/ArduCopter/mode_flip.cpp @@ -1,5 +1,7 @@ #include "Copter.h" +#if MODE_FLIP_ENABLED == ENABLED + /* * Init and run calls for flip flight mode * original implementation in 2010 by Jose Julio @@ -222,3 +224,5 @@ void Copter::ModeFlip::run() // output pilot's throttle without angle boost attitude_control->set_throttle_out(throttle_out, false, g.throttle_filt); } + +#endif