Copter: 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:
Randy Mackay 2016-07-21 21:45:00 +09:00
parent 61844b3062
commit f4db4bdb08
2 changed files with 9 additions and 0 deletions

View File

@ -955,6 +955,13 @@ void GCS_MAVLINK_Copter::handle_change_alt_request(AP_Mission::Mission_Command &
// To-Do: update target altitude for loiter or waypoint controller depending upon nav mode
}
void GCS_MAVLINK_Copter::packetReceived(const mavlink_status_t &status,
mavlink_message_t &msg)
{
copter.avoidance_adsb.handle_msg(msg);
GCS_MAVLINK::packetReceived(status, msg);
}
void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
{
uint8_t result = MAV_RESULT_FAILED; // assume failure. Each messages id is responsible for return ACK or NAK if required

View File

@ -20,4 +20,6 @@ private:
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;
};