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

Copter/AC_PosControl/Scripting: slung payload oscillation suppression #27783

Merged
merged 26 commits into from
Oct 4, 2024

Conversation

rmackay9
Copy link
Contributor

@rmackay9 rmackay9 commented Aug 7, 2024

This PR has expanded from its original scope to now add support for 3D position, velocity and acceleration offsets usable in all autonomous (e.g. Auto, Guide, RTL, etc) and semi-autonomous (e.g Loiter, PosHold, ZigZag, etc) modes.

This has been rigorously tested in SITL but it is a big change so any and all feedback is very welcome.


This adds slung payload oscillation suppression using a Lua script together with a new AC_PosControl feature that allows external callers (e.g. scripts) to add horizontal position or velocity offsets to the vehicle while flying in Auto mode.

The payload oscillation suppression only operates while the vehicle is in Auto mode executing a SCRIPT_TIME or PAYLOAD_PLACE command. E.g. it does not trying to reduce oscillation while the vehicle if flying towards a waypoint nor in any other flight mode. A blog post including video is here.

Changes include:

  1. SITL's slung payload simulator is enhance so that wind (e.g. SIM_WIND_SPD, SIM_WIND_DIR) affects the payload. This allows us to create an offsets between the slung payload and vehicle
  2. AC_PosControl gets new get/set methods for position and velocity offsets. External callers (including scripting) can use these to add offsets to the vehicle's target position or velocity
  3. AP_Vehicle/AP_Copter/AC_WPNav/AP_Scripting get equivalent new methods/bindings to set the position and velocity offsets (e.g. set_pos_offset, set_vel_offset). Perhaps we should rename/replace these if we want to support more modes besides Auto
  4. AP_Scripting's modules directory gets message definitions for GLOBAL_POSITION_INT and HEARTBEAT. We haven't normally added these but without them it makes it very difficult for normal users to use scripts that consume or sends these mavlink messages
  5. slung-payload.lua applet is added to AP_Scripting. This script only operates while the vehicle is in Auto mode executing a SCRIPT_TIME or PAYLOAD_PLACE command. It moves the vehicle towards the payload to reduce its oscillation with the speed of movement controlled by the SLUP_POS_P parameter. It also tries to estimate the payload's long-term position offset from the vehicle and slowly moves the vehicle in the opposite direction so that the package lands right on the waypoint. The speed of this movement can be adjusted using the SLUP_WP_POS_P parameter

This has been well tested in SITL and moderately well tested on a real vehicle:

  • checked that AC_PosControl position and velocity targets result in the expected behaviour. See screenshots below
    auto-offset-testing-screenshot
  • checked that the simulated payload lands precisely on the waypoint
  • checked that simulated wind affects the payload as expected (e.g. payload is pushed by the wind)
  • checked every navigation mission command with an offset of x=20m,y=20m to confirm they worked as expected

Video of SITL test: https://www.youtube.com/watch?v=jL2YUByYv2Y

Known issues we should fix before merging:

  • when switching between SCurve navigation and pure position control navigation the offsets are lost leading to a jump in the vehicle's position target. This happens in Auto mode when switching from a WAYPOINT command and PAYLOAD_PLACE
  • when switching from takeoff to SCurve navigation the SCurves seem to use twice the expected position offset

libraries/AC_WPNav/AC_WPNav.h Outdated Show resolved Hide resolved
ArduCopter/Copter.cpp Outdated Show resolved Hide resolved
Copy link
Contributor

@lthall lthall left a comment

Choose a reason for hiding this comment

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

I have done my first pass and my initial focus is on just the position controller work. I think I have two general concerns:

  1. We don't handle xy and z in the same way. I think this can be handled with a small change.
  2. We have limited the input to just position or velocity when both these can be provided with higher order inputs ie. We can specify a moving position offset by specifying position, velocity and acceleration to achieve a more responsive offset target movement.

libraries/AC_AttitudeControl/AC_PosControl.cpp Outdated Show resolved Hide resolved
libraries/AC_AttitudeControl/AC_PosControl.h Outdated Show resolved Hide resolved
libraries/AC_AttitudeControl/AC_PosControl.h Outdated Show resolved Hide resolved
libraries/AC_AttitudeControl/AC_PosControl.cpp Outdated Show resolved Hide resolved
libraries/AC_AttitudeControl/AC_PosControl.cpp Outdated Show resolved Hide resolved
libraries/AC_AttitudeControl/AC_PosControl.cpp Outdated Show resolved Hide resolved
libraries/AC_AttitudeControl/AC_PosControl.cpp Outdated Show resolved Hide resolved
libraries/AC_AttitudeControl/AC_PosControl.cpp Outdated Show resolved Hide resolved
@IamPete1
Copy link
Member

Do we want to log the offsets all the time? For the PD scale stuff we added a new message that was only logged if they were set (not one in that case, not zero in your case).

tridge
tridge previously requested changes Sep 16, 2024
libraries/AC_AttitudeControl/AC_PosControl.h Outdated Show resolved Hide resolved
libraries/AP_Scripting/docs/docs.lua Outdated Show resolved Hide resolved
@rmackay9
Copy link
Contributor Author

rmackay9 commented Sep 16, 2024

This was discussed on the dev call and I'll make the following changes:

  • PSCx offsets will be logged to a new message PSCO (?)
  • Scripting bindings will use a new position controller object (instead of going through AP_Vehicle)
  • Check / change places where a reference has been replaced with an object to ensure the code is not doubling up on calculations. also consider moving from .h to .cpp

rmackay9 and others added 23 commits October 3, 2024 10:15
@lthall lthall self-requested a review October 3, 2024 12:27
Copy link
Contributor

@lthall lthall left a comment

Choose a reason for hiding this comment

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

I am very happy with this one.

libraries/AC_AttitudeControl/AC_PosControl.cpp Outdated Show resolved Hide resolved
libraries/AC_AttitudeControl/AC_PosControl.cpp Outdated Show resolved Hide resolved
libraries/AC_AttitudeControl/AC_PosControl.cpp Outdated Show resolved Hide resolved
ArduCopter/mode_auto.cpp Show resolved Hide resolved
libraries/AC_WPNav/AC_Circle.cpp Outdated Show resolved Hide resolved
libraries/AC_WPNav/AC_WPNav.cpp Outdated Show resolved Hide resolved
libraries/AC_AttitudeControl/AC_PosControl_Logging.cpp Outdated Show resolved Hide resolved
libraries/AC_AttitudeControl/AC_PosControl.cpp Outdated Show resolved Hide resolved
@rmackay9 rmackay9 merged commit be1c87f into ArduPilot:master Oct 4, 2024
99 checks passed
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.

5 participants