From 031830b5febccd34488d1f5823b3b438292b1605 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Fri, 29 Jun 2012 14:38:15 -0700 Subject: [PATCH] System.pde: Toy mode details for set_mode() --- ArduCopter/system.pde | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index f1b8f3926f..abdea16806 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -381,7 +381,8 @@ static void set_mode(byte mode) { // if we don't have GPS lock if(home_is_set == false){ - // our max mode should be + // THOR + // We don't care about Home if we don't have lock yet in Toy mode if(mode == TOY || mode == OF_LOITER){ // nothing }else if (mode > ALT_HOLD){ @@ -517,10 +518,14 @@ static void set_mode(byte mode) set_next_WP(¤t_loc); break; + // THOR + // These are the flight modes for Toy mode + // See the defines for the enumerated values case TOY: yaw_mode = YAW_TOY; roll_pitch_mode = ROLL_PITCH_TOY; throttle_mode = THROTTLE_MANUAL; + wp_control = NO_NAV_MODE; break; default: