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

Implement MAV_CMD_REQUEST_MESSAGE #14815

Merged
merged 18 commits into from
Jun 3, 2020

Conversation

dayjaby
Copy link
Contributor

@dayjaby dayjaby commented May 3, 2020

Describe problem solved by this pull request
Implementing the MAV_CMD_REQUEST_MESSAGE as described in #11441. So far only STORAGE_INFORMATION is supported.

I would like to use the opportunity and remind about one other PR, where all mavlink streams get their own file instead of having one bloated mavlink_messages.cpp: c1175e0
This would be helpful to get merged, otherwise I have double work here.

Describe your solution
When there is a stream with the same message ID, send the message once. Otherwise create a new stream, send the message once and delete the stream again.

Test data / coverage
Tested with QGC custom command file https://pastebin.com/maHNSQ1A:
image

@dayjaby dayjaby force-pushed the pr-mav_cmd_request_message branch 2 times, most recently from b36ae5b to 8d7f0e6 Compare May 3, 2020 12:00
@hamishwillee
Copy link
Contributor

hamishwillee commented May 3, 2020

Implementing the MAV_CMD_REQUEST_MESSAGE as described in #11441. So far only STORAGE_INFORMATION is supported.

Not strictly speaking true. The request message has a default implementation that just immediately sends the last message if a stream has been defined for the message. So provided a message has a stream already defined then the "default" will be sent out.

But yes, this does need work . Firstly because there are cases like storage information and CAMERA_IMAGE_CAPTURED that take parameters (so a specific implementation required). Secondly because the current implementation I think ignores param 7, which is supposed to set the destination of the message. If you could fix those problems then that would be awesome.

Edit. PS, so you may be able to undo the specific changes you made for AUTOPILOT_VERSION etc. FWIW splitting up the streams to separate files would certainly make it easier to work out what we can stream and what we can't

@dayjaby
Copy link
Contributor Author

dayjaby commented May 4, 2020

I meant "so far" as in the scope of this PR ;)

so you may be able to undo the specific changes you made for AUTOPILOT_VERSION etc.

what do you mean? Defining streams for those messages does make sense. It allows not only to use MAV_CMD_REQUEST_MESSAGE to request them, but also MAV_CMD_SET_MESSAGE_INTERVAL. Documenting it otherwise would be hard: "You can only request this particular subset of messages, but not set the interval for them".

Still trying to figure out the purpose of param7. For reference: mavlink/mavlink#1248

@hamishwillee
Copy link
Contributor

Hi @dayjaby

so you may be able to undo the specific changes you made for AUTOPILOT_VERSION etc.
what do you mean? Defining streams for those messages does make sense. It allows not only to use MAV_CMD_REQUEST_MESSAGE to request them, but also MAV_CMD_SET_MESSAGE_INTERVAL. Documenting it otherwise would be hard: "You can only request this particular subset of messages, but not set the interval for them".

Apologies. I had assumed these were already streamed - so you were just adding request message method to support the single request (which you would not need to do in most cases given the default implementation). Ignore me.

Re param7, as you say some context in mavlink/mavlink#1248 and mavlink/mavlink#1249. Essentially most messages are broadcast so they go to everyone. But some messages have target addresses - they are intended for specific recipients. So for example if I'm telling something I want logging messages, then I'm the only thing that cares about those and the logging message should have my address. Honestly, in most cases I doubt it will matter if these were also broadcast, but setting this parameter allows you to choose whether you respond to the requestor or everyone. HOpe that helps. We can chat verbally if you want via slack at some point - just ping me (I'm in AEST so right now is 5pm on Monday)

@julianoes julianoes requested review from bkueng and julianoes May 4, 2020 07:25
Copy link
Contributor

@julianoes julianoes left a comment

Choose a reason for hiding this comment

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

Thanks for that. See my inline comment.

} else if (cmd_mavlink.command == MAV_CMD_REQUEST_FLIGHT_INFORMATION) {
send_flight_information();

} else if (cmd_mavlink.command == MAV_CMD_REQUEST_STORAGE_INFORMATION) {
Copy link
Contributor

Choose a reason for hiding this comment

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

We will have to support these commands for backwards compatibility, I suppose.

Copy link
Contributor

Choose a reason for hiding this comment

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

Yes we will. This is why we need microservices versioning and the new command metadata stuff.

@julianoes
Copy link
Contributor

@dayjaby I hope it's ok that I just force-pushed to this PR and added some commits to support legacy commands. I'll do another iteration to try to address @bkueng's comments.

@dayjaby
Copy link
Contributor Author

dayjaby commented May 28, 2020

Looking great! So next step would be to add the broadcasting according to param7, right?

Default is -2, so the comments seems wrong.
This allows to send a message exactly once if requested.
Instead of creating the stream and deleting it again, we now create it
with a rate of 0 and trigger it once.

This should avoid heap fragmentation by continous allocations.
@julianoes julianoes changed the title WIP: Implement MAV_CMD_REQUEST_MESSAGE Implement MAV_CMD_REQUEST_MESSAGE May 28, 2020
@julianoes
Copy link
Contributor

Looking great! So next step would be to add the broadcasting according to param7, right?

I have not looked at that one. Let me check what this involves.

@julianoes
Copy link
Contributor

Hm. The broadcast thing seems very hard to implement because were just triggering the stream to send a message. Also, all the messages that I was just looking at are broadcast anyway.

@julianoes
Copy link
Contributor

@bkueng I would appreciate your review.

We only need to send them immediately if the interval is < 0 meaning
unlimited.
I think we can just directly use send() and don't need to use the
workaround of resetting the send flag to trigger one send.

Also, we don't need to override it if we don't need to check any params.
@dayjaby
Copy link
Contributor Author

dayjaby commented May 28, 2020

Hm. The broadcast thing seems very hard to implement because were just triggering the stream to send a message. Also, all the messages that I was just looking at are broadcast anyway.

But if the stream is not configured for other mavlink instances (or mavlink channel? what's the correct wording?), this code won't send them via these instances.

@julianoes
Copy link
Contributor

But if the stream is not configured for other mavlink instances (or mavlink channel? what's the correct wording?), this code won't send them via these instances.

Correct. It won't send it. I would say it's a limitation that we have for now. We basically don't support it as required by the spec. I don't see a trivial way to enable that right now, and I don't have a use-case, so I'm reluctant to do so.

@hamishwillee any suggestions how to proceed?

Copy link
Member

@bkueng bkueng left a comment

Choose a reason for hiding this comment

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

Looks good, remarked a couple of things.

@@ -0,0 +1,55 @@
#ifndef MAVLINK_STREAM_AUTOPILOT_VERSION_H
#define MAVLINK_STREAM_AUTOPILOT_VERSION_H
Copy link
Member

Choose a reason for hiding this comment

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

#pragma once + missing copyright header

Copy link
Contributor

Choose a reason for hiding this comment

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

Fixed in cce410a.

return send(hrt_absolute_time());
}
private:
int storage_id = 0;
Copy link
Member

Choose a reason for hiding this comment

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

Suggested change
int storage_id = 0;
int _storage_id = 0;

Copy link
Contributor

Choose a reason for hiding this comment

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

Fixed in 1ec5d5d.

bool ret = _armed_sub.copy(&actuator_armed);

if (ret && actuator_armed.timestamp != 0) {
const param_t param_com_flight_uuid = param_find("COM_FLIGHT_UUID");
Copy link
Member

Choose a reason for hiding this comment

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

Can you keep that as class member and initialize in the constructor?

Copy link
Contributor

Choose a reason for hiding this comment

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

Fixed in 1ec5d5d.

{
bool stream_found = false;

for (const auto stream : _mavlink->get_streams()) {
Copy link
Member

Choose a reason for hiding this comment

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

Just to be consistent:

Suggested change
for (const auto stream : _mavlink->get_streams()) {
for (const auto& stream : _mavlink->get_streams()) {

Below as well.

Copy link
Contributor

Choose a reason for hiding this comment

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

Fixed in 1ec5d5d.


for (const auto stream : _mavlink->get_streams()) {
if (stream->get_id() == message_id) {
stream_found = stream->request_message(param2, param3, param4, param5, param6, param7);
Copy link
Member

Choose a reason for hiding this comment

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

What if this returns false? I.e. the stream is in the list, but did not get updated.

Copy link
Contributor

Choose a reason for hiding this comment

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

Addressed in 403dcd8.

Our answer does not just depend on whether the stream was found but
whether we actually were able to send out an update.
@julianoes
Copy link
Contributor

Thanks for the review @bkueng. It should all be resolved now.

@hamishwillee
Copy link
Contributor

But if the stream is not configured for other mavlink instances (or mavlink channel? what's the correct wording?), this code won't send them via these instances.

Correct. It won't send it. I would say it's a limitation that we have for now. We basically don't support it as required by the spec. I don't see a trivial way to enable that right now, and I don't have a use-case, so I'm reluctant to do so.

@hamishwillee any suggestions how to proceed?

I THINK you're saying that if a message is required to be broadcast it should be sent out on all channels, but our implementation only streams out on the particular channel that received the message. So for example, if the MAV_CMD_REQUEST_MESSAGE came from a companion computer connected by serial the response would go to the companion, but not (say) to a GCS connected by Wifi.

Is that correct?

If so, IMO:

  1. This is a more general routing "problem" than this particular API. We should document that PX4 does not automatically route between interfaces/channels.
  2. Yes, it is fine that we don't try fix this here.
  3. What we must do though is respect the param 7 values being set to 0 (broadcast) or 1 (the target recipient addresses).
  4. The places I see potential probems we would have been a problem anyway. In practise I think that this should work in most cases.

@julianoes
Copy link
Contributor

So for example, if the MAV_CMD_REQUEST_MESSAGE came from a companion computer connected by serial the response would go to the companion, but not (say) to a GCS connected by Wifi.

Correct, assuming the companion and wifi are on separate MAVLink instances/ports in PX4 and not split at a later stage (e.g. in mavlink-router).

  1. Correct, it doesn't automatically but it can forward from one to another instance if "forwarding" is set (MAV_0_FORWARD)
  2. That would also be a lot of work. It would have to be implemented for each and every message, I think.

Thinking more about this I yet would want to see an actual use case where someone requests a message that they need sent out to someone else. I can't think of a case right now.

@julianoes
Copy link
Contributor

@bkueng are you ok if we merge this. Everything you raised should be fixed.

@hamishwillee
Copy link
Contributor

hamishwillee commented Jun 3, 2020

I think we should merge it too.

Thinking more about this I yet would want to see an actual use case where someone requests a message that they need sent out to someone else. I can't think of a case right now.

FWiW

Param updates emit PARAM_VALUE whenever any GCS changes a parameter, allowing all of them (in theory) to track changes. If two GCS were communicating on different channels then other GCS would not get the update.

Somewhat contrived, but this is the reason that broadcast routing says "send everywhere" is because you don't know what needs that message or on what channel it might live. But (also as already noted), if this sort of thing was a real /significant problem, we'd have addressed it already.

Copy link
Member

@bkueng bkueng left a comment

Choose a reason for hiding this comment

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

Can you cleanup the commits?

}
}

return (message_sent ? vehicle_command_ack_s::VEHICLE_RESULT_ACCEPTED : vehicle_command_ack_s::VEHICLE_RESULT_DENIED);
Copy link
Member

Choose a reason for hiding this comment

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

This is a bit unfortunate, as you get a denied when the topic was not updated. It's a rare case but we'll have to see if it causes issues.

Copy link
Contributor

Choose a reason for hiding this comment

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

Right, that's why we have to use copy() for some of the ones that we expect to use like this:
https://github.com/PX4/Firmware/pull/14815/files/b0ed9d5ca7f1d206fbdae2c0b415e90859bf2ba6#diff-c8466a5bb81a917a3cf7b4131c18f821R89

@julianoes
Copy link
Contributor

@bkueng how would you cleanup these commits exactly? I'm not sure what's best. I would rebase them as is.

@bkueng
Copy link
Member

bkueng commented Jun 3, 2020

I'd squash them if you don't find a good way to split (I don't see one either). 18 commits is just unnecessary for this.

@julianoes
Copy link
Contributor

julianoes commented Jun 3, 2020

Selection_005

It just makes me a bit sad squashing this when it would actually help the next reader.

I'd say it makes sense to squash all fixup commits, and then rebase the commits. No, not even that makes much sense.

@LorenzMeier
Copy link
Member

TLDR; I think the number of commits you've chosen makes perfectly sense, let's just not merge fixup commits.

I generally would advise doing rather more commits than less, but yes, please do not keep fixup commits in the history. A good rule of thumb is 20-50 lines of code changed in one consistent set of files per commit. So a couple days work should be 15-50 commits.

@julianoes
Copy link
Contributor

Ok. It's just that getting rid of the fixups is not trivial since it's adding headers to files that @dayjaby had added. So I could go back and add them back in where it belongs but it would take a bit of time for not much gain.

@julianoes
Copy link
Contributor

julianoes commented Jun 3, 2020

Alright, I think it's too much effort to perfectly rewrite history here and I see value (and no big problems) with the current commits, so I'm going to merge it. Thanks for the reviews.

And thanks to @dayjaby who did most of the work here!

@julianoes julianoes merged commit c37ba26 into PX4:master Jun 3, 2020
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.

None yet

5 participants