forked from Archive/PX4-Autopilot
mavlink delete unimplemented and deprecated handle_message_request_data_stream
This commit is contained in:
parent
c8aa262e85
commit
d2457467e7
|
@ -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)
|
||||
{
|
||||
|
|
|
@ -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);
|
||||
|
|
Loading…
Reference in New Issue