GCS_MAVLink: remove vestigial SERIAL_CONTROL_DEV_SHELL support

The HAL always returns nullptr so the function always returns, which is
handled already by the default.
This commit is contained in:
Thomas Watson 2024-08-02 22:07:42 -05:00 committed by Andrew Tridgell
parent 6c851c4ea3
commit abae008250
1 changed files with 0 additions and 6 deletions

View File

@ -74,12 +74,6 @@ void GCS_MAVLINK::handle_serial_control(const mavlink_message_t &msg)
AP::gps().lock_port(1, exclusive); AP::gps().lock_port(1, exclusive);
break; break;
#endif // AP_GPS_ENABLED #endif // AP_GPS_ENABLED
case SERIAL_CONTROL_DEV_SHELL:
stream = hal.util->get_shell_stream();
if (stream == nullptr) {
return;
}
break;
case SERIAL_CONTROL_SERIAL0 ... SERIAL_CONTROL_SERIAL9: { case SERIAL_CONTROL_SERIAL0 ... SERIAL_CONTROL_SERIAL9: {
// direct access to a SERIALn port // direct access to a SERIALn port
stream = port = AP::serialmanager().get_serial_by_id(packet.device - SERIAL_CONTROL_SERIAL0); stream = port = AP::serialmanager().get_serial_by_id(packet.device - SERIAL_CONTROL_SERIAL0);