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

Plugin for TUNNEL messages #1625

Merged
merged 4 commits into from
Sep 24, 2021
Merged

Plugin for TUNNEL messages #1625

merged 4 commits into from
Sep 24, 2021

Conversation

mortenfyhn
Copy link
Contributor

I wanted to use MAVLink TUNNEL messages to communicate between ROS and some hardware connected to the FCU. I made a MAVROS plugin that forwards tunnels between ROS and the FCU, in both directions, and a Tunnel message in mavros_msgs that mirrors the MAVLink message.

One thing I'm not sure about is how to best deal with the variable length payload field. In MAVLink, it's defined as a 128 size array, but I suppose the serializer makes sure to avoid sending a bunch of zeros if only some of the size is used. I've made it a uint8[128] in ros to enforce the maximum size, but I think that might mean the ROS messages always send the full 128 bytes. I could make it uint8[], but then I would need to handle the max size somewhere. (Maybe just a comment in the message definition, and a check in the plugin when it copies between the ROS and MAVLink messages?)

mavros_msgs/msg/Tunnel.msg Outdated Show resolved Hide resolved
mavros_msgs/msg/Tunnel.msg Show resolved Hide resolved
@mortenfyhn
Copy link
Contributor Author

I've fixed the cog generation now, and I've added a check on the payload length, so I don't try to std::copy out of bounds data if payload_length is accidentally set higher than what's allowed.

Copy link
Member

@vooon vooon left a comment

Choose a reason for hiding this comment

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

LGTM, Thanks!

@vooon vooon merged commit e47ab9d into mavlink:master Sep 24, 2021
@vooon
Copy link
Member

vooon commented Sep 24, 2021

Hmm, i'm thinking, what if make Tunnel.payload dynamically sized, then we could remove Tunnel.payload_length (as we have it in payload.size()).

@mortenfyhn mortenfyhn deleted the tunnel-plugin branch September 24, 2021 07:12
@mortenfyhn
Copy link
Contributor Author

That's absolutely an option.

So the error handling would then be:

  • Plugin receives a mavros tunnel message
  • Check payload.size(), print error and don't send if > 128

and

  • Plugin receives a mavlink tunnel message
  • Check payload_length, print error and don't send if > 128

The only downside I can see is that the mavros and mavlink messages would be less similar, so the user of the plugin needs to figure out that payload_length is just encoded in the array size and not in a separate field.

@vooon
Copy link
Member

vooon commented Sep 24, 2021

I think first option better.

In my opinion payload_length makes handling of that message harder, and only needed for mavlink to express dynamically sized payload.
So i suppose that we can just add a note to the message and that's it.

{
static constexpr auto max_payload_length =
sizeof(mavlink::common::msg::TUNNEL::payload) /
sizeof(mavlink::common::msg::TUNNEL::payload[0]);
Copy link
Member

Choose a reason for hiding this comment

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

Since payload is std::array i think better to use ::size().

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

Successfully merging this pull request may close these issues.

None yet

2 participants