Plane: GCS_MAVLink passes packets to AP_Avoidance

This allows treating GLOBAL_POSITION_INT packets from other vehicles in the same way as ADSB packets
This commit is contained in:
Tom Pittenger 2016-08-12 12:15:04 -07:00
parent 46ec812d6c
commit b564616db0
2 changed files with 8 additions and 0 deletions

View File

@ -1125,6 +1125,13 @@ void GCS_MAVLINK_Plane::handle_change_alt_request(AP_Mission::Mission_Command &c
plane.reset_offset_altitude();
}
void GCS_MAVLINK_Plane::packetReceived(const mavlink_status_t &status,
mavlink_message_t &msg)
{
plane.avoidance_adsb.handle_msg(msg);
GCS_MAVLINK::packetReceived(status, msg);
}
void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
{
switch (msg->msgid) {

View File

@ -19,5 +19,6 @@ private:
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;
void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override;
bool try_send_message(enum ap_message id) override;
void packetReceived(const mavlink_status_t &status, mavlink_message_t &msg) override;
};