diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index e0c248eb9b..7361fd58ea 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -281,13 +281,6 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg) handle_message_heartbeat(msg); break; - case MAVLINK_MSG_ID_REQUEST_DATA_STREAM: - if (_mavlink->accepting_commands()) { - handle_message_request_data_stream(msg); - } - - break; - case MAVLINK_MSG_ID_SYSTEM_TIME: handle_message_system_time(msg); break; @@ -1679,12 +1672,6 @@ MavlinkReceiver::handle_message_ping(mavlink_message_t *msg) } } -void -MavlinkReceiver::handle_message_request_data_stream(mavlink_message_t *msg) -{ - // REQUEST_DATA_STREAM is deprecated, please use SET_MESSAGE_INTERVAL instead -} - int MavlinkReceiver::set_message_interval(int msgId, float interval, int data_rate) { diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h index 685e743849..a4fb3a2369 100644 --- a/src/modules/mavlink/mavlink_receiver.h +++ b/src/modules/mavlink/mavlink_receiver.h @@ -141,7 +141,6 @@ private: void handle_message_rc_channels_override(mavlink_message_t *msg); void handle_message_heartbeat(mavlink_message_t *msg); void handle_message_ping(mavlink_message_t *msg); - void handle_message_request_data_stream(mavlink_message_t *msg); void handle_message_system_time(mavlink_message_t *msg); void handle_message_timesync(mavlink_message_t *msg); void handle_message_hil_sensor(mavlink_message_t *msg);