diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 0acde9dbed..9b26468498 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -161,7 +161,6 @@ NOINLINE void Copter::send_extended_status1(mavlink_channel_t chan) case RTL: case CIRCLE: case LAND: - case OF_LOITER: case POSHOLD: case BRAKE: control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL; diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index 2f6deb03f8..11083a46c8 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -95,7 +95,6 @@ enum autopilot_modes { RTL = 6, // automatic return to launching point CIRCLE = 7, // automatic circular flight with automatic throttle LAND = 9, // automatic landing with horizontal position control - OF_LOITER = 10, // deprecated DRIFT = 11, // semi-automous position, yaw and throttle control SPORT = 13, // manual earth-frame angular rate control with manual throttle FLIP = 14, // automatically flip the vehicle on the roll axis diff --git a/ArduCopter/flight_mode.cpp b/ArduCopter/flight_mode.cpp index 6d4390ceb1..7a8637fa43 100644 --- a/ArduCopter/flight_mode.cpp +++ b/ArduCopter/flight_mode.cpp @@ -352,9 +352,6 @@ void Copter::print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode) case LAND: port->print("LAND"); break; - case OF_LOITER: - port->print("OF_LOITER"); - break; case DRIFT: port->print("DRIFT"); break;