GCS_MAVLink: Add conditions and delete the same processing

This commit is contained in:
muramura 2024-09-18 07:21:58 +09:00 committed by Peter Barker
parent 231eebe553
commit c0d14ec397

View File

@ -3212,17 +3212,12 @@ MAV_RESULT GCS_MAVLINK::handle_command_get_message_interval(const mavlink_comman
}
uint16_t interval_ms = 0;
if (!get_ap_message_interval(id, interval_ms)) {
if (!get_ap_message_interval(id, interval_ms) || interval_ms == 0) {
// not streaming this message at the moment...
mavlink_msg_message_interval_send(chan, mavlink_id, -1); // disabled
return MAV_RESULT_ACCEPTED;
}
if (interval_ms == 0) {
mavlink_msg_message_interval_send(chan, mavlink_id, -1); // disabled
return MAV_RESULT_ACCEPTED;
}
mavlink_msg_message_interval_send(chan, mavlink_id, interval_ms * 1000);
return MAV_RESULT_ACCEPTED;
}