GCS_MAVLink: remove msg_snoop functionality
inherit from GCS_MAVLink if you want to see mavlink traffic
This commit is contained in:
parent
484d97597b
commit
ac1a00739c
@ -101,9 +101,6 @@ public:
|
||||
virtual void data_stream_send(void) = 0;
|
||||
void queued_param_send();
|
||||
void queued_waypoint_send();
|
||||
void set_snoop(void (*_msg_snoop)(const mavlink_message_t* msg)) {
|
||||
msg_snoop = _msg_snoop;
|
||||
}
|
||||
// packetReceived is called on any successful decode of a mavlink message
|
||||
virtual void packetReceived(const mavlink_status_t &status,
|
||||
mavlink_message_t &msg);
|
||||
@ -425,10 +422,6 @@ private:
|
||||
|
||||
// send an async parameter reply
|
||||
void send_parameter_reply(void);
|
||||
|
||||
|
||||
// a vehicle can optionally snoop on messages for other systems
|
||||
static void (*msg_snoop)(const mavlink_message_t* msg);
|
||||
|
||||
virtual bool handle_guided_request(AP_Mission::Mission_Command &cmd) = 0;
|
||||
virtual void handle_change_alt_request(AP_Mission::Mission_Command &cmd) = 0;
|
||||
|
@ -848,10 +848,6 @@ void GCS_MAVLINK::packetReceived(const mavlink_status_t &status,
|
||||
cstatus->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
|
||||
}
|
||||
}
|
||||
// if a snoop handler has been setup then use it
|
||||
if (msg_snoop != nullptr) {
|
||||
msg_snoop(&msg);
|
||||
}
|
||||
if (routing.check_and_forward(chan, &msg) &&
|
||||
accept_packet(status, msg)) {
|
||||
handleMessage(&msg);
|
||||
|
@ -49,10 +49,6 @@ MAVLink_routing GCS_MAVLINK::routing;
|
||||
// static AP_SerialManager pointer
|
||||
const AP_SerialManager *GCS_MAVLINK::serialmanager_p;
|
||||
|
||||
// snoop function for vehicle types that want to see messages for
|
||||
// other targets
|
||||
void (*GCS_MAVLINK::msg_snoop)(const mavlink_message_t* msg) = nullptr;
|
||||
|
||||
/*
|
||||
lock a channel, preventing use by MAVLink
|
||||
*/
|
||||
|
Loading…
Reference in New Issue
Block a user