mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: Fix typos
This commit is contained in:
parent
e31a37e7a8
commit
3f92a64b99
|
@ -248,7 +248,7 @@ void MAVLink_routing::learn_route(mavlink_channel_t in_channel, const mavlink_me
|
|||
|
||||
/*
|
||||
special handling for heartbeat messages. To ensure routing
|
||||
propogation heartbeat messages need to be forwarded on all channels
|
||||
propagation heartbeat messages need to be forwarded on all channels
|
||||
except channels where the sysid/compid of the heartbeat could come from
|
||||
*/
|
||||
void MAVLink_routing::handle_heartbeat(mavlink_channel_t in_channel, const mavlink_message_t* msg)
|
||||
|
|
|
@ -50,7 +50,7 @@ void loop(void)
|
|||
err_count++;
|
||||
}
|
||||
|
||||
// incoming targetted message for someone else
|
||||
// incoming targeted message for someone else
|
||||
mavlink_param_set_t param_set = {0};
|
||||
param_set.target_system = mavlink_system.sysid+1;
|
||||
param_set.target_component = mavlink_system.compid;
|
||||
|
@ -60,7 +60,7 @@ void loop(void)
|
|||
err_count++;
|
||||
}
|
||||
|
||||
// incoming targetted message for us
|
||||
// incoming targeted message for us
|
||||
param_set.target_system = mavlink_system.sysid;
|
||||
param_set.target_component = mavlink_system.compid;
|
||||
mavlink_msg_param_set_encode(3, 1, &msg, ¶m_set);
|
||||
|
@ -69,7 +69,7 @@ void loop(void)
|
|||
err_count++;
|
||||
}
|
||||
|
||||
// incoming targetted message for our system, but other compid
|
||||
// incoming targeted message for our system, but other compid
|
||||
// should be processed locally
|
||||
param_set.target_system = mavlink_system.sysid;
|
||||
param_set.target_component = mavlink_system.compid+1;
|
||||
|
|
Loading…
Reference in New Issue