diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 3c6eca9674..bda55be404 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -365,8 +365,6 @@ private: uint8_t count; uint8_t ch_flag; } aux_debounce[(CH_12 - CH_7)+1]; - // altitude below which we do no navigation in auto takeoff - float auto_takeoff_no_nav_alt_cm; RCMapper rcmap; @@ -919,9 +917,6 @@ private: const char* get_frame_string(); void allocate_motors(void); - void auto_takeoff_set_start_alt(void); - void auto_takeoff_attitude_run(float target_yaw_rate); - // terrain.cpp void terrain_update(); void terrain_logging(); diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index f812c6f7d1..1668e4097a 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -31,6 +31,8 @@ Copter::Mode::Mode(void) : ekfNavVelGainScaler(copter.ekfNavVelGainScaler) { }; +float Copter::Mode::auto_takeoff_no_nav_alt_cm = 0; + // return the static controller object corresponding to supplied mode Copter::Mode *Copter::mode_from_mode_num(const uint8_t mode) { diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index 0e5d9e6fb3..eeecd7246a 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -160,6 +160,10 @@ protected: // method shared by both Guided and Auto for takeoff. This is // waypoint navigation but the user can control the yaw. void auto_takeoff_run(); + void auto_takeoff_set_start_alt(void); + void auto_takeoff_attitude_run(float target_yaw_rate); + // altitude below which we do no navigation in auto takeoff + static float auto_takeoff_no_nav_alt_cm; // gnd speed limit required to observe optical flow sensor limits float &ekfGndSpdLimit; diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index 09d66dd3fc..354e8bffe6 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -176,7 +176,7 @@ void Copter::ModeAuto::takeoff_start(const Location& dest_loc) set_throttle_takeoff(); // get initial alt for WP_NAVALT_MIN - copter.auto_takeoff_set_start_alt(); + auto_takeoff_set_start_alt(); } // auto_wp_start - initialises waypoint controller to implement flying to a particular destination diff --git a/ArduCopter/mode_guided.cpp b/ArduCopter/mode_guided.cpp index 1ee7f7c2ac..506793d218 100644 --- a/ArduCopter/mode_guided.cpp +++ b/ArduCopter/mode_guided.cpp @@ -71,7 +71,7 @@ bool Copter::ModeGuided::do_user_takeoff_start(float final_alt_above_home) set_throttle_takeoff(); // get initial alt for WP_NAVALT_MIN - copter.auto_takeoff_set_start_alt(); + auto_takeoff_set_start_alt(); return true; } @@ -409,7 +409,7 @@ void Copter::Mode::auto_takeoff_run() copter.pos_control->update_z_controller(); // call attitude controller - copter.auto_takeoff_attitude_run(target_yaw_rate); + auto_takeoff_attitude_run(target_yaw_rate); } // guided_pos_control_run - runs the guided position controller diff --git a/ArduCopter/takeoff.cpp b/ArduCopter/takeoff.cpp index 0c70aa0fca..25fa9eefbb 100644 --- a/ArduCopter/takeoff.cpp +++ b/ArduCopter/takeoff.cpp @@ -135,7 +135,7 @@ void Copter::Mode::_TakeOff::get_climb_rates(float& pilot_climb_rate, } } -void Copter::auto_takeoff_set_start_alt(void) +void Copter::Mode::auto_takeoff_set_start_alt(void) { // start with our current altitude auto_takeoff_no_nav_alt_cm = inertial_nav.get_altitude(); @@ -151,7 +151,7 @@ void Copter::auto_takeoff_set_start_alt(void) call attitude controller for automatic takeoff, limiting roll/pitch if below wp_navalt_min */ -void Copter::auto_takeoff_attitude_run(float target_yaw_rate) +void Copter::Mode::auto_takeoff_attitude_run(float target_yaw_rate) { float nav_roll, nav_pitch; @@ -161,7 +161,7 @@ void Copter::auto_takeoff_attitude_run(float target_yaw_rate) nav_pitch = 0; #if FRAME_CONFIG == HELI_FRAME // prevent hover roll starting till past specified altitude - hover_roll_trim_scalar_slew = 0; + copter.hover_roll_trim_scalar_slew = 0; #endif // tell the position controller that we have limited roll/pitch demand to prevent integrator buildup pos_control->set_limit_accel_xy();