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

Added re-initialization for guided_change_x commands #27236

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

Conversation

EyesWider
Copy link

Currently ArduPilot supports MAV_CMD_DO_REPOSITION for latitude/longitude and altitude control in Guided mode, and MAV_CMD_DO_CHANGE_SPEED can be used to control the aircraft's speed. These messages together allow aircraft "Waypoint" control.

MAV_CMD_GUIDED_CHANGE_SPEED, MAV_CMD_GUIDED_CHANGE_ALTITUDE, and MAV_CMD_GUIDED_CHANGE_HEADING can also be used in Guided mode, and support slewing the aircraft to align to the respective Heading, Speed, Altitude (HSA) commands. However, currently there is no logic implemented to stop listening to these commands while in Guided for any reason, with the result that any MAV_CMD_DO_REPOSITION or MAV_CMD_DO_CHANGE_SPEED commands sent after conflicting HSA commands are Accepted but functionally ignored. The result is that for a companion computer to transition back to Waypoint commands after sending HSA commands, the only way to do this is for the computer or the pilot to command out of Guided and then back in.

These updates perform the same re-initialization of the HSA-related variables that currently happens when entering Guided, but does it whenever a DO_REPOSITION or DO_CHANGE_SPEED command is Accepted. There may be additional messages where it would also make sense to do this re-initialization, or in a different location - I am not sure.

@@ -859,6 +859,13 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_int_do_reposition(const mavlink_com
plane.mode_guided.set_radius_and_direction(packet.param3, requested_position.loiter_ccw);
}

// Need to re-initialize these, otherwise DO_REPOSITION will be overruled by GUIDED_CHANGE_HEADING and GUIDED_CHANGE_ALTITUDE if previously sent
Copy link
Member

Choose a reason for hiding this comment

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

This should be in a common guided reset method that would also be called in the mode change case.

Copy link
Author

Choose a reason for hiding this comment

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

Done!

Copy link
Member

Choose a reason for hiding this comment

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

Nice! Much better! Could they go in the ModeGuided in https://github.com/ArduPilot/ardupilot/blob/master/ArduPlane/mode_guided.cpp

Copy link
Author

Choose a reason for hiding this comment

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

Done as well! Thanks, still learning the code layout.

@rmackay9
Copy link
Contributor

rmackay9 commented Jun 7, 2024

Hi @EyesWider,

Thanks very much for this. A bit of admin, could you rebase on master to remove the merge commits? Also we like to have all our commits prefixed with the directory (or subsystem) that is affected because it makes backporting easier. .. so could you rename the commit title (not to be confused with the PR title) so that it starts with "Plane: "

@rmackay9 rmackay9 added the Plane label Jun 7, 2024
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.

This looks like it's a good idea. A few things:

  • Randy points out commit-style issues; see https://ardupilot.org/dev/docs/git-interactive-rebase.html
  • IMO there should be three commits here:
    • one which makes the functions and calls them where you're extracting the code from
    • one which adds autotests for the functionality you're adding here
      • i.e. do some offboard guided, then do a reposition and test for the problem
    • one which calls the new functions and causes the test to then pass

I'm a bit concerned that the current approach is a bit whack-a-mole, You've adjusted code in the reposition code, and in the do-change-speed code - but surely there are other places that we should "snap out" of being in this offboard-guided mode. For example, receiving a change-altitude command. One option there would be to have a proper submode setup in there.

This is why I'd like the separate commit that creates the methods; separates re-arrangement from logic changes.

Comment on lines +145 to +147
void reset_guided_hdg();
void reset_guided_alt();
void reset_guided_spd();
Copy link
Contributor

Choose a reason for hiding this comment

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

Remove

@peterbarker
Copy link
Contributor

Ping @timtuxworth - you've been working in here. Your thoughts?

@EyesWider sorry, conflicting on Tim's work. Could you rebase, please?

@timtuxworth
Copy link
Contributor

timtuxworth commented Sep 10, 2024

Ping @timtuxworth - you've been working in here. Your thoughts?

@EyesWider sorry, conflicting on Tim's work. Could you rebase, please?

Thanks Peter, yes I have seen exactly this and documented it in this (unfinished) Wiki PR. ArduPilot/ardupilot_wiki#6096

I have a different fix for the same issue in my PR #27137 at GCS_Mavlink.cpp:858 but this looks like a cleaner and more complete solution than mine.

@timtuxworth
Copy link
Contributor

My PR #27921 has been merged @EyesWider - it would be great if you could rebase and update this, I'd really like to see it merged.

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

Successfully merging this pull request may close these issues.

5 participants