mirror of https://github.com/ArduPilot/ardupilot
Copter: explain msgs handling in packetReceived
This commit is contained in:
parent
400c65ce5d
commit
b7e0b1ad38
|
@ -577,6 +577,7 @@ bool GCS_MAVLINK_Copter::handle_guided_request(AP_Mission::Mission_Command &cmd)
|
|||
void GCS_MAVLINK_Copter::packetReceived(const mavlink_status_t &status,
|
||||
const mavlink_message_t &msg)
|
||||
{
|
||||
// we handle these messages here to avoid them being blocked by mavlink routing code
|
||||
#if HAL_ADSB_ENABLED
|
||||
if (copter.g2.dev_options.get() & DevOptionADSBMAVLink) {
|
||||
// optional handling of GLOBAL_POSITION_INT as a MAVLink based avoidance source
|
||||
|
|
Loading…
Reference in New Issue