mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 18:38:28 -04:00
Copter: remove err msg for undefined throttle mode
Printing errors like this to the console are unlikely to ever be seen
This commit is contained in:
parent
284aa2217f
commit
8a886c0e19
@ -1910,11 +1910,6 @@ bool set_throttle_mode( uint8_t new_throttle_mode )
|
|||||||
controller_desired_alt = get_initial_alt_hold(current_loc.alt, climb_rate); // reset controller desired altitude to current altitude
|
controller_desired_alt = get_initial_alt_hold(current_loc.alt, climb_rate); // reset controller desired altitude to current altitude
|
||||||
throttle_initialised = true;
|
throttle_initialised = true;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
default:
|
|
||||||
// To-Do: log an error message to the dataflash or tlogs instead of printing to the serial port
|
|
||||||
cliSerial->printf_P(PSTR("Unsupported throttle mode: %d!!"),new_throttle_mode);
|
|
||||||
break;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// update the throttle mode
|
// update the throttle mode
|
||||||
|
Loading…
Reference in New Issue
Block a user