mirror of https://github.com/ArduPilot/ardupilot
Tracker: process mavlink msgs from vehicle once
previously heartbeat messages from the vehicle could be processed twice. Once at the top of hte handleMessage function where they were forwarded onto the GCS and then again lower down in the function where all received heartbeats were sent to the vehicle.
This commit is contained in:
parent
7a06ed8a8a
commit
3e62b188a1
|
@ -434,10 +434,7 @@ GCS_MAVLINK::data_stream_send(void)
|
|||
|
||||
void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
{
|
||||
if (g.proxy_mode == true)
|
||||
{
|
||||
if (chan == proxy_vehicle.chan)
|
||||
{
|
||||
if (g.proxy_mode == true && chan == proxy_vehicle.chan) {
|
||||
// From the remote vehicle.
|
||||
// All messages from the remote are proxied to GCS
|
||||
// We also eavesdrop on MAVLINK_MSG_ID_GLOBAL_POSITION_INT and MAVLINK_MSG_ID_SCALED_PRESSUREs
|
||||
|
@ -472,9 +469,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
// Else its from the GCS, and it might be for the remote and.or it might be for the tracker
|
||||
// So we fall through to the below
|
||||
// no further processing of messages from vehicle
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
|
|
Loading…
Reference in New Issue