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:
Randy Mackay 2013-09-24 20:47:29 +09:00
parent 284aa2217f
commit 8a886c0e19
1 changed files with 0 additions and 5 deletions

View File

@ -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
throttle_initialised = true;
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