Copter: Flip mode is an option.

Copter: Flip mode is an option.
This commit is contained in:
murata 2018-11-26 08:47:55 +09:00 committed by Randy Mackay
parent 3ee675ad42
commit b252eae404
5 changed files with 15 additions and 0 deletions

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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:

View File

@ -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