Improve message handling in mavlink IRIDIUM mode

- Do not send any mission updates as they are handled within HIGH_LATENCY2
- Always send a command acknowledge even if transmitting is not enabled
This commit is contained in:
acfloria 2018-03-05 14:25:34 +01:00 committed by Beat Küng
parent 32815dc1d3
commit edd337880d
2 changed files with 9 additions and 0 deletions

View File

@ -2236,7 +2236,11 @@ Mavlink::task_main(int argc, char *argv[])
msg.target_component = command_ack.target_component;
current_command_ack = command_ack.command;
// always transmit the acknowledge
bool _transmitting_enabled_temp = _transmitting_enabled;
_transmitting_enabled = true;
mavlink_msg_command_ack_send_struct(get_channel(), &msg);
_transmitting_enabled = _transmitting_enabled_temp;
}
}

View File

@ -479,6 +479,11 @@ MavlinkMissionManager::send_mission_item_reached(uint16_t seq)
void
MavlinkMissionManager::send(const hrt_abstime now)
{
// do not send anything over high latency communication
if (_mavlink->get_mode() == Mavlink::MAVLINK_MODE_IRIDIUM) {
return;
}
bool updated = false;
orb_check(_mission_result_sub, &updated);