mirror of https://github.com/ArduPilot/ardupilot
Rover: Check MANUAL_CONTROL target
This commit is contained in:
parent
e840006ff9
commit
3bad3b2e68
|
@ -975,6 +975,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;
|
||||
|
|
Loading…
Reference in New Issue