mirror of https://github.com/ArduPilot/ardupilot
Sub: Remove Drift mode
This commit is contained in:
parent
bc4084931f
commit
41d892666b
|
@ -734,9 +734,6 @@ private:
|
|||
void autotune_twitching_measure_acceleration(float &rate_of_change, float rate_measurement, float &rate_measurement_max);
|
||||
bool circle_init(bool ignore_checks);
|
||||
void circle_run();
|
||||
bool drift_init(bool ignore_checks);
|
||||
void drift_run();
|
||||
float get_throttle_assist(float velz, float pilot_throttle_scaled);
|
||||
bool guided_init(bool ignore_checks);
|
||||
bool guided_takeoff_start(float final_alt_above_home);
|
||||
void guided_pos_control_start();
|
||||
|
|
|
@ -108,7 +108,6 @@ enum control_mode_t {
|
|||
CIRCLE = 7, // not implemented in sub // automatic circular flight with automatic throttle
|
||||
SURFACE = 9, // automatically return to surface, pilot maintains horizontal control
|
||||
OF_LOITER = 10, // deprecated
|
||||
DRIFT = 11, // not implemented in sub // semi-automous position, yaw and throttle control
|
||||
TRANSECT = 13, // automatic x/y velocity, automatic heading/crosstrack error compensation, automatic depth/throttle
|
||||
AUTOTUNE = 15, // not implemented in sub // automatically tune the vehicle's roll and pitch gains
|
||||
POSHOLD = 16, // automatic position hold with manual override, with automatic throttle
|
||||
|
|
|
@ -63,10 +63,6 @@ bool Sub::set_mode(control_mode_t mode, mode_reason_t reason)
|
|||
success = rtl_init(ignore_checks);
|
||||
break;
|
||||
|
||||
case DRIFT:
|
||||
success = drift_init(ignore_checks);
|
||||
break;
|
||||
|
||||
#if TRANSECT_ENABLED == ENABLED
|
||||
case TRANSECT:
|
||||
success = transect_init(ignore_checks);
|
||||
|
@ -174,10 +170,6 @@ void Sub::update_flight_mode()
|
|||
rtl_run();
|
||||
break;
|
||||
|
||||
case DRIFT:
|
||||
drift_run();
|
||||
break;
|
||||
|
||||
#if TRANSECT_ENABLED == ENABLED
|
||||
case TRANSECT:
|
||||
transect_run();
|
||||
|
@ -250,7 +242,6 @@ bool Sub::mode_requires_GPS(control_mode_t mode) {
|
|||
case VELHOLD:
|
||||
case RTL:
|
||||
case CIRCLE:
|
||||
case DRIFT:
|
||||
case POSHOLD:
|
||||
case THROW:
|
||||
case TRANSECT:
|
||||
|
@ -279,7 +270,7 @@ bool Sub::mode_has_manual_throttle(control_mode_t mode) {
|
|||
// mode_allows_arming - returns true if vehicle can be armed in the specified mode
|
||||
// arming_from_gcs should be set to true if the arming request comes from the ground station
|
||||
bool Sub::mode_allows_arming(control_mode_t mode, bool arming_from_gcs) {
|
||||
if (mode_has_manual_throttle(mode) || mode == VELHOLD || mode == ALT_HOLD || mode == POSHOLD || mode == DRIFT || mode == TRANSECT || mode == THROW || (arming_from_gcs && mode == GUIDED)) {
|
||||
if (mode_has_manual_throttle(mode) || mode == VELHOLD || mode == ALT_HOLD || mode == POSHOLD || mode == TRANSECT || mode == THROW || (arming_from_gcs && mode == GUIDED)) {
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
|
@ -339,9 +330,6 @@ void Sub::print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode)
|
|||
case OF_LOITER:
|
||||
port->print("OF_LOITER");
|
||||
break;
|
||||
case DRIFT:
|
||||
port->print("DRIFT");
|
||||
break;
|
||||
case TRANSECT:
|
||||
port->print("TRANSECT");
|
||||
break;
|
||||
|
|
Loading…
Reference in New Issue