Tracker: GCS_Mavlink format fix-up of indentation

This commit is contained in:
Randy Mackay 2014-09-29 21:06:33 +09:00
parent 3e62b188a1
commit 111ec147f0
1 changed files with 31 additions and 31 deletions

View File

@ -434,13 +434,11 @@ GCS_MAVLINK::data_stream_send(void)
void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
{
// in proxy mode all messages from the vehicle are proxied to GCS
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
switch (msg->msgid)
{
// We also eavesdrop on MAVLINK_MSG_ID_GLOBAL_POSITION_INT and MAVLINK_MSG_ID_SCALED_PRESSUREs
switch (msg->msgid) {
case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
{
// decode
@ -459,6 +457,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break;
}
}
// Proxy to all the GCS stations
for (uint8_t i=0; i<num_gcs; i++) {
if (gcs[i].initialised) {
@ -469,7 +468,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
}
}
}
// no further processing of messages from vehicle
// no further processing of this messages
return;
}