mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
GCS_MAVLink: fix set-default-rate of a message we don't send by default
this fixes a problem where a GCS must know that a message isn't sent by default if they want to set it back to its default rate
This commit is contained in:
parent
6b0dd7e689
commit
6c3f9f9778
@ -749,7 +749,6 @@ private:
|
||||
// if true is returned, interval will contain the default interval for id
|
||||
bool get_default_interval_for_ap_message(const ap_message id, uint16_t &interval) const;
|
||||
// if true is returned, interval will contain the default interval for id
|
||||
bool get_default_interval_for_mavlink_message_id(const uint32_t mavlink_message_id, uint16_t &interval) const;
|
||||
// returns an interval in milliseconds for any ap_message in stream id
|
||||
uint16_t get_interval_for_stream(GCS_MAVLINK::streams id) const;
|
||||
// set an inverval for a specific mavlink message. Returns false
|
||||
|
@ -2659,11 +2659,24 @@ MAV_RESULT GCS_MAVLINK::handle_command_set_message_interval(const mavlink_comman
|
||||
|
||||
MAV_RESULT GCS_MAVLINK::set_message_interval(uint32_t msg_id, int32_t interval_us)
|
||||
{
|
||||
const ap_message id = mavlink_id_to_ap_message_id(msg_id);
|
||||
if (id == MSG_LAST) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "No ap_message for mavlink id (%u)", (unsigned int)msg_id);
|
||||
return MAV_RESULT_DENIED;
|
||||
}
|
||||
|
||||
uint16_t interval_ms;
|
||||
if (interval_us == 0) {
|
||||
// zero is "reset to default rate"
|
||||
if (!get_default_interval_for_mavlink_message_id(msg_id, interval_ms)) {
|
||||
return MAV_RESULT_FAILED;
|
||||
if (!get_default_interval_for_ap_message(id, interval_ms)) {
|
||||
// if we don't have a default interval then we assume that
|
||||
// we do not send that message by default. That may not
|
||||
// be strictly true if some random piece of code has set a
|
||||
// rate as part of its initialisation - in which case that
|
||||
// piece of code should probably be adding something into
|
||||
// whatever get_default_interval_for_ap_message is looking
|
||||
// at.
|
||||
interval_ms = 0;
|
||||
}
|
||||
} else if (interval_us == -1) {
|
||||
// minus-one is "stop sending"
|
||||
@ -2676,7 +2689,7 @@ MAV_RESULT GCS_MAVLINK::set_message_interval(uint32_t msg_id, int32_t interval_u
|
||||
} else {
|
||||
interval_ms = interval_us / 1000;
|
||||
}
|
||||
if (set_mavlink_message_id_interval(msg_id, interval_ms)) {
|
||||
if (set_ap_message_interval(id, interval_ms)) {
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
|
||||
@ -6017,16 +6030,6 @@ bool GCS_MAVLINK::get_default_interval_for_ap_message(const ap_message id, uint1
|
||||
return false;
|
||||
}
|
||||
|
||||
bool GCS_MAVLINK::get_default_interval_for_mavlink_message_id(const uint32_t mavlink_message_id, uint16_t &interval) const
|
||||
{
|
||||
const ap_message id = mavlink_id_to_ap_message_id(mavlink_message_id);
|
||||
if (id == MSG_LAST) {
|
||||
return false;
|
||||
}
|
||||
|
||||
return get_default_interval_for_ap_message(id, interval);
|
||||
}
|
||||
|
||||
/*
|
||||
correct an offboard timestamp in microseconds into a local timestamp
|
||||
since boot in milliseconds. See the JitterCorrection code for details
|
||||
|
Loading…
Reference in New Issue
Block a user