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

MAV_CMD_SET_MESSAGE_INTERVAL reject non-zero values for unused params #23643

Open
wants to merge 3 commits into
base: main
Choose a base branch
from
Open
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
13 changes: 8 additions & 5 deletions src/modules/mavlink/mavlink_receiver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -593,12 +593,13 @@ void MavlinkReceiver::handle_message_command_both(mavlink_message_t *msg, const
result = handle_request_message_command(MAVLINK_MSG_ID_STORAGE_INFORMATION);

} else if (cmd_mavlink.command == MAV_CMD_SET_MESSAGE_INTERVAL) {
if (set_message_interval((int)roundf(cmd_mavlink.param1), cmd_mavlink.param2, cmd_mavlink.param3)) {
if (set_message_interval((int)(cmd_mavlink.param1 + 0.5f), cmd_mavlink.param2, cmd_mavlink.param3, cmd_mavlink.param4,
(int)(vehicle_command.param5 + 0.5), (int)(vehicle_command.param6 + 0.5), (int)(vehicle_command.param7 + 0.5f))) {
hamishwillee marked this conversation as resolved.
Show resolved Hide resolved
result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_FAILED;
}

} else if (cmd_mavlink.command == MAV_CMD_GET_MESSAGE_INTERVAL) {
get_message_interval((int)roundf(cmd_mavlink.param1));
get_message_interval((int)(cmd_mavlink.param1 + 0.5f));

} else if (cmd_mavlink.command == MAV_CMD_REQUEST_MESSAGE) {

Expand Down Expand Up @@ -2273,14 +2274,16 @@ MavlinkReceiver::handle_message_heartbeat(mavlink_message_t *msg)
}

int
MavlinkReceiver::set_message_interval(int msgId, float interval, int data_rate)
MavlinkReceiver::set_message_interval(int msgId, float interval, float param3, float param4, int param5, int param6,
int response_target)
{
if (msgId == MAVLINK_MSG_ID_HEARTBEAT) {
return PX4_ERROR;
}

if (data_rate > 0) {
_mavlink.set_data_rate(data_rate);
if ((int)(param3 + 0.5f) || (int)(param4 + 0.5f) || param5 || param6 || response_target) {
// At least one of the unsupported params is non-zero
return PX4_ERROR;
Comment on lines +2284 to +2286
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm just wondering if this could trigger when a param with NAN instead of 0 is sent and whether it's the right approach to respond with error in that case instead of just ignoring it.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I want this to trigger if any of those params are non-zero, including if they were NaN.
But I think this is OK, because my understanding is that NaN evaluates as false in C++.

and whether it's the right approach to respond with error in that case instead of just ignoring it.

It would technically be an error because the default value for a reserved param in mavlink is defined as 0 if unspecified. If you want the default value to be NaN then you have to put that in the XML.

It could "really" matter in this case if we decided that NaN had meaning for those parameters other than "do nothing". That does happen sometimes. Making it a 0 check is safer.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

But I think this is OK, because my understanding is that NaN evaluates as false in C++.

Hm, I was assuming NAN + 0.5 is NAN and NAN cast to int will be some odd number which is not zero.

Let's see:
According to this it would be "undefined", which is not something we should rely on:
https://stackoverflow.com/questions/3986795/what-is-the-result-of-casting-float-inf-inf-and-nan-to-integer-in-c

In my own try, it seems to be -INT_MAX or 0, so very much undefined:
https://godbolt.org/z/Wd7qxM5T9

}

// configure_stream wants a rate (msgs/second), so convert here.
Expand Down
4 changes: 2 additions & 2 deletions src/modules/mavlink/mavlink_receiver.h
Original file line number Diff line number Diff line change
Expand Up @@ -230,11 +230,11 @@ class MavlinkReceiver : public ModuleParams
*
* @param msgId The ID of the message interval to be set.
* @param interval The interval in usec to send the message.
* @param data_rate The total link data rate in bytes per second.
*
* @return PX4_OK on success, PX4_ERROR on fail.
*/
int set_message_interval(int msgId, float interval, int data_rate = -1);
int set_message_interval(int msgId, float interval, float param3 = 0.0f, float param4 = 0.0f, int param5 = 0,
int param6 = 0, int response_target = 0);
void get_message_interval(int msgId);

bool evaluate_target_ok(int command, int target_system, int target_component);
Expand Down
Loading