Copter: remove OF_LOITER entirely

This commit is contained in:
Jonathan Challinger 2015-12-28 14:02:43 -08:00 committed by Randy Mackay
parent d969154391
commit 0e85f55cfc
3 changed files with 0 additions and 5 deletions

View File

@ -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;

View File

@ -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

View File

@ -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;