diff --git a/ArduPlane/commands.cpp b/ArduPlane/commands.cpp index f410cd0a0d..7d0f089bc2 100644 --- a/ArduPlane/commands.cpp +++ b/ArduPlane/commands.cpp @@ -55,10 +55,6 @@ void Plane::set_next_WP(const struct Location &loc) prev_WP_loc = current_loc; } - // used to control FBW and limit the rate of climb - // ----------------------------------------------- - set_target_altitude_location(next_WP_loc); - // zero out our loiter vals to watch for missed waypoints loiter_angle_reset();