From f58f8048e2bdea92113b09c4f1aec116a100b1d1 Mon Sep 17 00:00:00 2001 From: lordneeko Date: Thu, 12 Apr 2018 08:09:57 -0400 Subject: [PATCH] Update mode_flip.cpp Update comments for new available modes to Flip from --- ArduCopter/mode_flip.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/mode_flip.cpp b/ArduCopter/mode_flip.cpp index 4dc6d9d1c..5586730a0 100644 --- a/ArduCopter/mode_flip.cpp +++ b/ArduCopter/mode_flip.cpp @@ -7,7 +7,7 @@ * * Controls: * CH7_OPT - CH12_OPT parameter must be set to "Flip" (AUXSW_FLIP) which is "2" - * Pilot switches to Stabilize, Acro or AltHold flight mode and puts ch7/ch8 switch to ON position + * Pilot switches to Stabilize, Acro, AltHold, FlowHold, or Loiter flight mode and puts ch7/ch8 switch to ON position * Vehicle will Roll right by default but if roll or pitch stick is held slightly left, forward or back it will flip in that direction * Vehicle should complete the roll within 2.5sec and will then return to the original flight mode it was in before flip was triggered * Pilot may manually exit flip by switching off ch7/ch8 or by moving roll stick to >40deg left or right @@ -88,7 +88,7 @@ Copter::ModeFlip::ModeFlip(void) : Mode() // flip_init - initialise flip controller bool Copter::ModeFlip::init(bool ignore_checks) { - // only allow flip from ACRO, Stabilize, AltHold or Drift flight modes + // only allow flip from ACRO, Stabilize, AltHold, FlowHold or Loiter flight modes if (copter.control_mode != ACRO && copter.control_mode != STABILIZE && copter.control_mode != ALT_HOLD &&