Rover: check target of set-mode request from GCS

Issue discovered and fix contributed by Deadolous
This commit is contained in:
Randy Mackay 2014-09-27 11:44:17 +09:00 committed by Andrew Tridgell
parent 6d3acba04c
commit 2dbfc6158d

View File

@ -918,6 +918,11 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
mavlink_set_mode_t packet;
mavlink_msg_set_mode_decode(msg, &packet);
// exit immediately if this command is not meant for this vehicle
if (mavlink_check_target(packet.target_system, 0)) {
break;
}
if (!(packet.base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED)) {
// we ignore base_mode as there is no sane way to map
// from that bitmap to a APM flight mode. We rely on
@ -1025,6 +1030,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
int16_t v[8];
mavlink_msg_rc_channels_override_decode(msg, &packet);
// exit immediately if this command is not meant for this vehicle
if (mavlink_check_target(packet.target_system,packet.target_component))
break;