Browse Source

Sub: Remove unused flight modes

mission-4.1.18
Jacob Walser 8 years ago committed by Randy Mackay
parent
commit
40a27814e0
  1. 1
      ArduSub/GCS_Mavlink.cpp
  2. 2
      ArduSub/defines.h
  3. 3
      ArduSub/flight_mode.cpp

1
ArduSub/GCS_Mavlink.cpp

@ -146,7 +146,6 @@ NOINLINE void Sub::send_extended_status1(mavlink_channel_t chan)
case VELHOLD: case VELHOLD:
case CIRCLE: case CIRCLE:
case SURFACE: case SURFACE:
case OF_LOITER:
case POSHOLD: case POSHOLD:
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL; control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL; control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL;

2
ArduSub/defines.h

@ -95,10 +95,8 @@ enum control_mode_t {
AUTO = 3, // not implemented in sub // fully automatic waypoint control using mission commands AUTO = 3, // not implemented in sub // fully automatic waypoint control using mission commands
GUIDED = 4, // not implemented in sub // fully automatic fly to coordinate or fly at velocity/direction using GCS immediate commands GUIDED = 4, // not implemented in sub // fully automatic fly to coordinate or fly at velocity/direction using GCS immediate commands
VELHOLD = 5, // automatic x/y velocity control and automatic depth/throttle VELHOLD = 5, // automatic x/y velocity control and automatic depth/throttle
// RTL = 6, // not implemented in sub // automatic return to launching point
CIRCLE = 7, // not implemented in sub // automatic circular flight with automatic throttle CIRCLE = 7, // not implemented in sub // automatic circular flight with automatic throttle
SURFACE = 9, // automatically return to surface, pilot maintains horizontal control SURFACE = 9, // automatically return to surface, pilot maintains horizontal control
OF_LOITER = 10, // deprecated
POSHOLD = 16, // automatic position hold with manual override, with automatic throttle POSHOLD = 16, // automatic position hold with manual override, with automatic throttle
MANUAL = 19 // Pass-through input with no stabilization MANUAL = 19 // Pass-through input with no stabilization
}; };

3
ArduSub/flight_mode.cpp

@ -263,9 +263,6 @@ void Sub::print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode)
case SURFACE: case SURFACE:
port->print("SURFACE"); port->print("SURFACE");
break; break;
case OF_LOITER:
port->print("OF_LOITER");
break;
case POSHOLD: case POSHOLD:
port->print("POSHOLD"); port->print("POSHOLD");
break; break;

Loading…
Cancel
Save