Rover: Check MANUAL_CONTROL target

This commit is contained in:
Michael du Breuil 2018-04-03 16:20:51 -07:00 committed by Francisco Ferreira
parent e840006ff9
commit 3bad3b2e68
1 changed files with 4 additions and 0 deletions

View File

@ -976,6 +976,10 @@ void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
mavlink_manual_control_t packet;
mavlink_msg_manual_control_decode(msg, &packet);
if (packet.target != rover.g.sysid_this_mav) {
break; // only accept control aimed at us
}
const int16_t roll = (packet.y == INT16_MAX) ? 0 : rover.channel_steer->get_radio_min() + (rover.channel_steer->get_radio_max() - rover.channel_steer->get_radio_min()) * (packet.y + 1000) / 2000.0f;
const int16_t throttle = (packet.z == INT16_MAX) ? 0 : rover.channel_throttle->get_radio_min() + (rover.channel_throttle->get_radio_max() - rover.channel_throttle->get_radio_min()) * (packet.z + 1000) / 2000.0f;
hal.rcin->set_override(uint8_t(rover.rcmap.roll() - 1), roll);