From e4559bbf5cfd9f8c2613f96a198e18fbf09f226f Mon Sep 17 00:00:00 2001 From: Jason Short Date: Mon, 12 Dec 2011 10:20:15 -0800 Subject: [PATCH] Added param option for Simple mode reset --- ArduCopter/ArduCopter.pde | 7 ++++--- ArduCopter/Parameters.h | 4 ++++ ArduCopter/config.h | 4 ++++ 3 files changed, 12 insertions(+), 3 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 1619845fd5..fcc382913b 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -568,6 +568,8 @@ AP_Relay relay; static bool usb_connected; #endif +static float roll_I; +static float pitch_I; //////////////////////////////////////////////////////////////////////////////// // Top-level logic @@ -1261,10 +1263,9 @@ static void update_navigation() } // are we in SIMPLE mode? - if(do_simple){ + if(do_simple && g.reset_simple){ // get distance to home - if(home_distance > 10){ - // 10m + if(home_distance > 10){ // 10m from home // we reset the angular offset to be a vector from home to the quad initial_simple_bearing = home_to_copter_bearing; //Serial.printf("ISB: %d\n", initial_simple_bearing); diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 1bd53b77d0..2e40f43225 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -106,6 +106,7 @@ public: k_param_low_voltage, k_param_ch7_option, k_param_sonar_type, // 153 + k_param_reset_simple, // // 160: Navigation parameters @@ -200,6 +201,8 @@ public: AP_Int8 optflow_enabled; AP_Float input_voltage; AP_Float low_voltage; + AP_Int8 reset_simple; + // Waypoints // @@ -315,6 +318,7 @@ public: optflow_enabled (OPTFLOW, k_param_optflow_enabled, PSTR("FLOW_ENABLE")), input_voltage (INPUT_VOLTAGE, k_param_input_voltage, PSTR("IN_VOLT")), low_voltage (LOW_VOLTAGE, k_param_low_voltage, PSTR("LOW_VOLT")), + reset_simple (RESET_SIMPLE, k_param_reset_simple, PSTR("RST_SIMPL")), waypoint_mode (0, k_param_waypoint_mode, PSTR("WP_MODE")), command_total (0, k_param_command_total, PSTR("WP_TOTAL")), diff --git a/ArduCopter/config.h b/ArduCopter/config.h index bd066a82fd..ae4d6cd402 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -468,6 +468,10 @@ # define RTL_THR THROTTLE_HOLD #endif +#ifndef RESET_SIMPLE +# define RESET_SIMPLE DISABLED +#endif +