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

Conversation

hamishwillee
Copy link
Contributor

@hamishwillee hamishwillee commented Sep 5, 2024

MAVLink recently added additional params to allow specific instances of messages to be streamed with MAV_CMD_SET_MESSAGE_INTERVAL following the same pattern as MAV_CMD_REQUEST_MESSAGE in mavlink/mavlink#2148

Specifically, this allows us to tell as specific camera attached to a flight stack that we want it to stream, but it can be used for any purpose.

This updates PX4 to reject the command if it has non-zero values for unused parameters.

A couple of notes:

  1. Param 3 was being used to set overall data rates if the value was > 0. This is non-compliant with the spec and not documented anywhere (not even sure how it would work). If this is needed then MAVLink needs to be updated. I have removed this from being set from param3.
    @julianoes This is a concern. Do we need to try make this data_rate thing actually be in MAVLink? Any thoughts on how to check if it is used?
  2. param7, response_target is supposed to set where the response is returned. 0 means "do whatever you like". If any other value is set, this now returns 0.
  3. param 3, 4, 5, 6 all return error of denied if the params are non-zero. So at least a recipient knows that these are not supported. We can fix up if we do want to allow specific cases to return ids.

@julianoes No urgency. Added you as a reviewer because you know my C++ is weak and will look at this properly.

src/modules/mavlink/mavlink_receiver.cpp Outdated Show resolved Hide resolved
src/modules/mavlink/mavlink_receiver.cpp Outdated Show resolved Hide resolved
src/modules/mavlink/mavlink_receiver.cpp Outdated Show resolved Hide resolved
@hamishwillee
Copy link
Contributor Author

Thanks @julianoes - I removed data rate from the signature and method, but left setter/getter on the MAVLink class (even though not used).

@hamishwillee
Copy link
Contributor Author

Cool. Do I need to worry about those SITL fails?

@julianoes
Copy link
Contributor

Don't know. Can you rebase on top of main and force push?

@hamishwillee
Copy link
Contributor Author

@julianoes Tried it, same problem. I also update #23664 and that does work, so this is likely something to do with my code. Next step to try the test code locally? Are there instructions for that anywhere?

@julianoes
Copy link
Contributor

It's broken in main as well, so not you.

Comment on lines +2284 to +2286
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;
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

@hamishwillee
Copy link
Contributor Author

I wonder if I should wait for main to be fixed or merge this then ...

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants