Browse Source

Plane: Check MANUAL_CONTROL target

mission-4.1.18
Michael du Breuil 7 years ago committed by Francisco Ferreira
parent
commit
1af2155641
  1. 8
      ArduPlane/GCS_Mavlink.cpp

8
ArduPlane/GCS_Mavlink.cpp

@ -1418,11 +1418,17 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg) @@ -1418,11 +1418,17 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
case MAVLINK_MSG_ID_MANUAL_CONTROL:
{
if (msg->sysid != plane.g.sysid_my_gcs) break; // Only accept control from our gcs
if (msg->sysid != plane.g.sysid_my_gcs) {
break; // only accept control from our gcs
}
mavlink_manual_control_t packet;
mavlink_msg_manual_control_decode(msg, &packet);
if (packet.target != plane.g.sysid_this_mav) {
break; // only accept messages aimed at us
}
bool override_active = false;
int16_t roll = (packet.y == INT16_MAX) ? 0 : plane.channel_roll->get_radio_min() + (plane.channel_roll->get_radio_max() - plane.channel_roll->get_radio_min()) * (packet.y + 1000) / 2000.0f;
int16_t pitch = (packet.x == INT16_MAX) ? 0 : plane.channel_pitch->get_radio_min() + (plane.channel_pitch->get_radio_max() - plane.channel_pitch->get_radio_min()) * (-packet.x + 1000) / 2000.0f;

Loading…
Cancel
Save