diff --git a/ArduCopter/control_althold.cpp b/ArduCopter/control_althold.cpp index c63fe5bd6b..cf6872aebe 100644 --- a/ArduCopter/control_althold.cpp +++ b/ArduCopter/control_althold.cpp @@ -21,8 +21,10 @@ bool Copter::althold_init(bool ignore_checks) pos_control.set_accel_z(g.pilot_accel_z); // initialise position and desired velocity - pos_control.set_alt_target(inertial_nav.get_altitude()); - pos_control.set_desired_velocity_z(inertial_nav.get_velocity_z()); + if (!pos_control.is_active_z()) { + pos_control.set_alt_target_to_current_alt(); + pos_control.set_desired_velocity_z(inertial_nav.get_velocity_z()); + } // stop takeoff if running takeoff_stop(); diff --git a/ArduCopter/control_auto.cpp b/ArduCopter/control_auto.cpp index 6c1252cd62..7063677cf3 100644 --- a/ArduCopter/control_auto.cpp +++ b/ArduCopter/control_auto.cpp @@ -361,8 +361,10 @@ void Copter::auto_land_start(const Vector3f& destination) wp_nav.init_loiter_target(destination); // initialise position and desired velocity - pos_control.set_alt_target(inertial_nav.get_altitude()); - pos_control.set_desired_velocity_z(inertial_nav.get_velocity_z()); + if (!pos_control.is_active_z()) { + pos_control.set_alt_target(inertial_nav.get_altitude()); + pos_control.set_desired_velocity_z(inertial_nav.get_velocity_z()); + } // initialise yaw set_auto_yaw_mode(AUTO_YAW_HOLD); diff --git a/ArduCopter/control_autotune.cpp b/ArduCopter/control_autotune.cpp index 38a3eb2a8c..765f8fbabc 100644 --- a/ArduCopter/control_autotune.cpp +++ b/ArduCopter/control_autotune.cpp @@ -246,8 +246,10 @@ bool Copter::autotune_start(bool ignore_checks) pos_control.set_accel_z(g.pilot_accel_z); // initialise position and desired velocity - pos_control.set_alt_target(inertial_nav.get_altitude()); - pos_control.set_desired_velocity_z(inertial_nav.get_velocity_z()); + if (!pos_control.is_active_z()) { + pos_control.set_alt_target_to_current_alt(); + pos_control.set_desired_velocity_z(inertial_nav.get_velocity_z()); + } return true; } diff --git a/ArduCopter/control_brake.cpp b/ArduCopter/control_brake.cpp index 2e7f762d1b..6b46533867 100644 --- a/ArduCopter/control_brake.cpp +++ b/ArduCopter/control_brake.cpp @@ -22,8 +22,10 @@ bool Copter::brake_init(bool ignore_checks) pos_control.set_accel_z(BRAKE_MODE_DECEL_RATE); // initialise position and desired velocity - pos_control.set_alt_target(inertial_nav.get_altitude()); - pos_control.set_desired_velocity_z(inertial_nav.get_velocity_z()); + if (!pos_control.is_active_z()) { + pos_control.set_alt_target_to_current_alt(); + pos_control.set_desired_velocity_z(inertial_nav.get_velocity_z()); + } brake_timeout_ms = 0; diff --git a/ArduCopter/control_guided.cpp b/ArduCopter/control_guided.cpp index d1f6d48630..6c90605d73 100644 --- a/ArduCopter/control_guided.cpp +++ b/ArduCopter/control_guided.cpp @@ -156,8 +156,10 @@ void Copter::guided_angle_control_start() pos_control.set_accel_z(wp_nav.get_accel_z()); // initialise position and desired velocity - pos_control.set_alt_target(inertial_nav.get_altitude()); - pos_control.set_desired_velocity_z(inertial_nav.get_velocity_z()); + if (!pos_control.is_active_z()) { + pos_control.set_alt_target_to_current_alt(); + pos_control.set_desired_velocity_z(inertial_nav.get_velocity_z()); + } // initialise targets guided_angle_state.update_time_ms = millis(); diff --git a/ArduCopter/control_land.cpp b/ArduCopter/control_land.cpp index d45d619718..758d07e3e4 100644 --- a/ArduCopter/control_land.cpp +++ b/ArduCopter/control_land.cpp @@ -24,8 +24,10 @@ bool Copter::land_init(bool ignore_checks) pos_control.set_accel_z(wp_nav.get_accel_z()); // initialise position and desired velocity - pos_control.set_alt_target(inertial_nav.get_altitude()); - pos_control.set_desired_velocity_z(inertial_nav.get_velocity_z()); + if (!pos_control.is_active_z()) { + pos_control.set_alt_target_to_current_alt(); + pos_control.set_desired_velocity_z(inertial_nav.get_velocity_z()); + } land_start_time = millis(); diff --git a/ArduCopter/control_loiter.cpp b/ArduCopter/control_loiter.cpp index d84430e5d3..c34f7c3518 100644 --- a/ArduCopter/control_loiter.cpp +++ b/ArduCopter/control_loiter.cpp @@ -26,8 +26,10 @@ bool Copter::loiter_init(bool ignore_checks) pos_control.set_accel_z(g.pilot_accel_z); // initialise position and desired velocity - pos_control.set_alt_target(inertial_nav.get_altitude()); - pos_control.set_desired_velocity_z(inertial_nav.get_velocity_z()); + if (!pos_control.is_active_z()) { + pos_control.set_alt_target_to_current_alt(); + pos_control.set_desired_velocity_z(inertial_nav.get_velocity_z()); + } return true; }else{ diff --git a/ArduCopter/control_poshold.cpp b/ArduCopter/control_poshold.cpp index 12c009b2c7..e7277aaa95 100644 --- a/ArduCopter/control_poshold.cpp +++ b/ArduCopter/control_poshold.cpp @@ -87,8 +87,10 @@ bool Copter::poshold_init(bool ignore_checks) pos_control.set_accel_z(g.pilot_accel_z); // initialise position and desired velocity - pos_control.set_alt_target(inertial_nav.get_altitude()); - pos_control.set_desired_velocity_z(inertial_nav.get_velocity_z()); + if (!pos_control.is_active_z()) { + pos_control.set_alt_target_to_current_alt(); + pos_control.set_desired_velocity_z(inertial_nav.get_velocity_z()); + } // initialise lean angles to current attitude poshold.pilot_roll = 0; diff --git a/ArduCopter/control_rtl.cpp b/ArduCopter/control_rtl.cpp index 13ad80a8b2..7932eb246e 100644 --- a/ArduCopter/control_rtl.cpp +++ b/ArduCopter/control_rtl.cpp @@ -350,8 +350,10 @@ void Copter::rtl_land_start() wp_nav.init_loiter_target(wp_nav.get_wp_destination()); // initialise position and desired velocity - pos_control.set_alt_target(inertial_nav.get_altitude()); - pos_control.set_desired_velocity_z(inertial_nav.get_velocity_z()); + if (!pos_control.is_active_z()) { + pos_control.set_alt_target_to_current_alt(); + pos_control.set_desired_velocity_z(inertial_nav.get_velocity_z()); + } // initialise yaw set_auto_yaw_mode(AUTO_YAW_HOLD); diff --git a/ArduCopter/control_sport.cpp b/ArduCopter/control_sport.cpp index 06d75866e0..762a0be598 100644 --- a/ArduCopter/control_sport.cpp +++ b/ArduCopter/control_sport.cpp @@ -14,8 +14,10 @@ bool Copter::sport_init(bool ignore_checks) pos_control.set_accel_z(g.pilot_accel_z); // initialise position and desired velocity - pos_control.set_alt_target(inertial_nav.get_altitude()); - pos_control.set_desired_velocity_z(inertial_nav.get_velocity_z()); + if (!pos_control.is_active_z()) { + pos_control.set_alt_target_to_current_alt(); + pos_control.set_desired_velocity_z(inertial_nav.get_velocity_z()); + } return true; }