Browse Source

GCS_MAVLink: added accept_packet() hook

this will allow vehicles to control whether packets are accepted by
GCS sysid or not
master
Andrew Tridgell 9 years ago
parent
commit
f01f711ff6
  1. 4
      libraries/GCS_MAVLink/GCS.h
  2. 3
      libraries/GCS_MAVLink/GCS_Common.cpp

4
libraries/GCS_MAVLink/GCS.h

@ -225,6 +225,10 @@ public: @@ -225,6 +225,10 @@ public:
protected:
// overridable method to check for packet acceptance. Allows for
// enforcement of GCS sysid
virtual bool accept_packet(const mavlink_status_t &status, mavlink_message_t &msg) { return true; }
bool waypoint_receiving; // currently receiving
// the following two variables are only here because of Tracker
uint16_t waypoint_request_i; // request index

3
libraries/GCS_MAVLink/GCS_Common.cpp

@ -985,7 +985,8 @@ void GCS_MAVLINK::packetReceived(const mavlink_status_t &status, @@ -985,7 +985,8 @@ void GCS_MAVLINK::packetReceived(const mavlink_status_t &status,
if (msg_snoop != NULL) {
msg_snoop(&msg);
}
if (routing.check_and_forward(chan, &msg)) {
if (routing.check_and_forward(chan, &msg) &&
accept_packet(status, msg)) {
handleMessage(&msg);
}
}

Loading…
Cancel
Save