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: GCS_Common: Add support to MAV_CMD_DO_SET_SYS_CMP_ID #26424

Open
wants to merge 3 commits into
base: master
Choose a base branch
from

Conversation

patrickelectric
Copy link
Member

libraries/GCS_MAVLink/GCS_Common.cpp Outdated Show resolved Hide resolved
libraries/GCS_MAVLink/GCS_Common.cpp Show resolved Hide resolved
return MAV_RESULT_FAILED;
}

if (!AP_Param::set_and_save_by_name("SYSID_THISMAV", new_system_id)) {
Copy link
Contributor

Choose a reason for hiding this comment

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

Should check we're not setting the same value into the parameter that it already has here.

Unless it is not configured in storage, in which case we may or may not want to save it....

Copy link
Member Author

Choose a reason for hiding this comment

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

Changed to: set_and_save_by_name_ifchanged

}

if (do_reboot) {
hal.scheduler->reboot(false);
Copy link
Contributor

Choose a reason for hiding this comment

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

If this returns then there's been a failure, so we should not return ACCEPTED.

Copy link
Member Author

Choose a reason for hiding this comment

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

What should we return ?

Copy link
Contributor

Choose a reason for hiding this comment

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

MAV_RESULT_FAILED looks appropriate.

Copy link
Member Author

Choose a reason for hiding this comment

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

I'm not sure if I follow you logic here. I just moved the reboot action to a late_reboot. The idea is to allow the vehicle to ACK the command before rebooting.

{
const uint8_t new_system_id = packet.param1;
const uint8_t new_component_id = packet.param2;
const uint8_t do_reboot = packet.param3;
Copy link
Contributor

Choose a reason for hiding this comment

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

Should this be a "reboot" or "this change should take effect immediately" flag?

Copy link
Member Author

Choose a reason for hiding this comment

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

Copy link
Contributor

Choose a reason for hiding this comment

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

Yep, we read the message description.

The intent is for the thing to take effect immediately, 'though, isn't it? We can probably do that without a reboot my modifying the mavlink state variables.

I think this field should probably be "take effect immediately", rather than "reboot". We can discuss at DevCallEU tonight if you like....

Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
const uint8_t new_component_id = packet.param2;
const uint8_t do_reboot = packet.param3;

if (new_system_id == 0 || hal.util->get_soft_armed()) {
Copy link
Contributor

Choose a reason for hiding this comment

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

I wonder why we need to reject the command if new_system_id is zero (apart from "that's what the message says")

This means you can't tell a system to just change its component ID.

... but you can tell it to just change its system ID. This is weird.

Copy link
Member Author

Choose a reason for hiding this comment

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

The entire explanation of the message logic is here: mavlink/mavlink#2082 (comment)

In a system with multiple components per vehicle, accepting a broadcast will change all components to a single component_id, and that would be terrible. The only way to change the component ID is to communicate with it directly. You can change all components to the same system_id though.

Copy link
Contributor

@peterbarker peterbarker left a comment

Choose a reason for hiding this comment

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

... we should also work out where the ACK gets sent from.

I think we need to send the ACK from the old address, which might make this a little interesting...

Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
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

4 participants