mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
GCS_MAVLink: Add conditions and delete the same processing
This commit is contained in:
parent
231eebe553
commit
c0d14ec397
@ -3212,17 +3212,12 @@ MAV_RESULT GCS_MAVLINK::handle_command_get_message_interval(const mavlink_comman
|
|||||||
}
|
}
|
||||||
|
|
||||||
uint16_t interval_ms = 0;
|
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...
|
// not streaming this message at the moment...
|
||||||
mavlink_msg_message_interval_send(chan, mavlink_id, -1); // disabled
|
mavlink_msg_message_interval_send(chan, mavlink_id, -1); // disabled
|
||||||
return MAV_RESULT_ACCEPTED;
|
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);
|
mavlink_msg_message_interval_send(chan, mavlink_id, interval_ms * 1000);
|
||||||
return MAV_RESULT_ACCEPTED;
|
return MAV_RESULT_ACCEPTED;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user