Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

GCS_MAVLink: fix set-default-rate of a message we don't send by default #21947

Merged
merged 2 commits into from
Oct 17, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 4 additions & 3 deletions Tools/autotest/common.py
Original file line number Diff line number Diff line change
Expand Up @@ -9269,7 +9269,7 @@ def test_set_message_interval_basic(self):
# this assumes the streamrates have not been played with:
self.test_rate("Resetting original rate using 0-value", 0, rate)
self.test_rate("Disabling using -1-value", -1, 0)
self.test_rate("Resetting original rate", rate, rate)
self.test_rate("Resetting original rate", 0, rate)

self.progress("try getting a message which is not ordinarily streamed out")
rate = round(self.get_message_rate("CAMERA_FEEDBACK", 20))
Expand Down Expand Up @@ -9310,8 +9310,9 @@ def test_set_message_interval_basic(self):
self.print_exception_caught(e)
ex = e

self.progress("Resetting CAMERA_FEEDBACK rate to zero")
self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_CAMERA_FEEDBACK, -1)
self.progress("Resetting CAMERA_FEEDBACK rate to default rate")
self.set_message_rate_hz(mavutil.mavlink.MAVLINK_MSG_ID_CAMERA_FEEDBACK, 0)
self.assert_message_rate_hz('CAMERA_FEEDBACK', 0)

if ex is not None:
raise ex
Expand Down
1 change: 0 additions & 1 deletion libraries/GCS_MAVLink/GCS.h
Original file line number Diff line number Diff line change
Expand Up @@ -749,7 +749,6 @@ class GCS_MAVLINK
// 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
Expand Down
29 changes: 16 additions & 13 deletions libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand All @@ -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;
}

Expand Down Expand Up @@ -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
Expand Down