mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
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:
parent
46ec812d6c
commit
b564616db0
@ -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) {
|
||||
|
@ -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;
|
||||
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user