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: Feature: Ship Landing #24720

Draft
wants to merge 10 commits into
base: master
Choose a base branch
from

Conversation

KosmX
Copy link

@KosmX KosmX commented Aug 21, 2023

Add ship landing feature to ArduCopter (moving base using precland)

  • Scripted PrecLand: LuaScript can set the precland target if PLND_TYPE is 5 (new)
  • Scripted velocity correction for takeoff (Velocity match)
  • LuaScript for landing
  • simulation files

Demo video (simulation):

https://kosmx.dev/vtol_landing_poc/copter/cop.webm

Moving platform landing was already implemented in precision landing, I only added a scripted PrecLand backend.
For approaching the ship, updating the waypoint does not work like it does in VTOL, I use FOLLOW mode for approach and changing mode to LAND when I'm above target.

@KosmX KosmX force-pushed the copter_shipland_extra branch 3 times, most recently from fa00144 to 6c17248 Compare August 22, 2023 10:42
set_target_location can be used by scripting to set the target.
This will require a scripted backend
the land target has to be set using set_target_location
from this, both direction and distance will be calculated.

If current location is unknown, relative target will not set, return false
If there was no update in the last second, backend will report target lost.
add set_target_location to land mode
 forwarding the parameter to PrecLand backend
This allow modes to use velocity match for example takeoff
velocity matching with moving platfom while takeoff
The landing will approach target in follow mode
then switch to PLND mode to land
@Georacer
Copy link
Contributor

Hi there! Very cool to see an attempt to support ship landing for Copter!

Is this effort still ongoing, or did you drop it by now?

@KosmX
Copy link
Author

KosmX commented Sep 26, 2023

It's not forgotten, I have the script, I just need to properly commit it. I might be able to do that next week

@Georacer
Copy link
Contributor

Excellent! I'm working on simulating such a system right now, so I'm willing to test.

@KosmX
Copy link
Author

KosmX commented Sep 27, 2023

I actually have simulation files (I was making this at summer, but I didn't have time to commit everything)

Here's a bit messy but probably working simulation stuff (and simulations for VTOL with 2 trucks)
sim.tar.gz

@Georacer
Copy link
Contributor

Georacer commented Sep 30, 2023

Hi again! I've managed to get the simulation working, more or less. I had to figure out a bit the various necessary paths, but nothing too hard.
So far I've had the two trucks stationary.

With limited experimentation, I've noticed that I have an issue with the RTL phase of the landing: I param set FOLL_SYSID 5 (trailer 2) and then take off and mode rtl.
Then the UA enters FOLLOW mode (as I think is expected), but targets an altitude of 0m immediately. This means that it flies diagonally under the trailer bed and crashes.

For reference notice how the UA reports being at 25m when it sits on trailer 1. Could this be part of the problem?

Or because I didn't use the SHIP_AUTO_OFS=1 to calibrate the landing point?

Screenshot from 2023-09-30 11-53-32

@KosmX
Copy link
Author

KosmX commented Sep 30, 2023

The altitude is calculated relative to home, and the home has to be offset by some altitude for the approach.

The approach happens in FOLLOW mode because waypoint updating doesn't really work for copters.
To approach in the air, the FOLL_OFS_Z is lowered by the approach altitude (in cm).
Because the altitude is calculated relative to home (which is the beacon), the home is corrected by this approach altitude SHIP_OFS_Z param.

To configure your copter correctly for landing, either use SHIP_AUTO_OFS (easiest and hard to mess up) or offset the FOLL_OFS_Z by the target altitude.
Don't forget to set SHIP_OFS_Z to set the target approach altitude.
line 285: FOLL_OFS_Z:set_and_save(new:z() - SHIP_OFS_Z:get())

@Georacer
Copy link
Contributor

Georacer commented Oct 1, 2023

Thanks for your answers! SHIP_OFS_Z seems to work as expected.

I've done some more experimenting today:


I have taken off from a moving truck. That seems to work OK: Velocity matching happens during ascent and once it is complete the UA comes to a stop.


I have then switched follow targets and landed on a stationary truck. That also seems to work OK.


I haven't had success trying to land on a moving truck: The UA goes after it and engages LAND, but it can't seem to get really close to start the descent, it just gets stuck keeping a constant offset from it. The picture shows an example of the situation:
Screenshot from 2023-10-01 21-01-40

@Georacer
Copy link
Contributor

Georacer commented Oct 5, 2023

I still can't reproduce the moving landing of your video. The UA switches to LAND mode when it gets close to the platform, but it keeps lagging behind at altitude, never getting close enough to descend. If I stop the tractor, then it reaches it and lands.

Another thing I noticed is that the throttle levels are not affected by the rc 3 XXXX commands I issue in the MAVProxy console, hence I can't test aborting the landing. But that's likely not your fault.

@KosmX
Copy link
Author

KosmX commented Oct 6, 2023

  • The close enough to start land depends on WP_RADIUS, you might need to increase this a little.
  • If there is no throttle control, the script will start landing without user input, that feature works (at least when tested with a physical copter)

@Georacer
Copy link
Contributor

Okay, I got some more testing done, and my first moving landing (although it's a bit lacking).

  • The close enough to start land depends on WP_RADIUS, you might need to increase this a little.
    This one doesn't exist in my system. I believe you mean WPNAV_RADIUS? That is at 200m in my current testing. And I even changed the conditional from 100 to 10 (rather hacky, but oh well...)
         if throttle_pos <= THROTTLE_MID and target_pos:get_distance_NE(current_pos):length() * 10 < WPNAV_RADIUS:get() then

to make sure I'm within landing limits. I don't think this is the problem.

What I noticed that made a change is setting param set PLND_XY_DIST_MAX 5. Only then will the copter start descending. And as you'd expect, it lands further back than it should
Screenshot from 2023-10-10 21-47-58

I believe that for some reason the PrecLand controller can't keep up with the moving trailer, but I don't know why yet.
Perhaps because my Gazebo seems to be running only at 30% real time? Perhaps the Home coordinates publication/forwarding rate is too low?
The velocity control seems to be OK during the Landing:
image
The position too:
image
(Detail)
image

So perhaps it's somewhere higher-up in the PrecLand logic?


One more piece of evidence: I noticed that while the copter is hovering at the final land maneuver, if I edit FOLL_OFS_X to something higher, the copter moves a bit forward as expected. Then if I set it back to its original value (typically -1.2), then as it moves back, it passes over this point and it will descend a bit more, as the XY error is small over the landing area.


I also noticed that sometimes the copter would not disarm once it touched down on the moving trailer. I don't know if it's trying to not go below Home altitude; I find this unlikely. If I set mid-air param set SHIP_OFS_Z 19 (1 lower than during param set SHIP_AUTO_OFS ) then I had more luck. But I did very limited testing on this.


Finally, I see you set PLND_TYPE=5, which AFAIU is not a documented value. Is this intentional?


Here's what I'm doing to reproduce your original instructions, mostly for my own sanity:

  • Cloned your repo (at branch KosmX/copter_shipland_extra)
  • Downloaded the .tar you sent and placed it next to the ardupilot folder, named it simulation.
  • I set up the ARDUPILOT_HOME and SITL_MODELS_DIR env variables.
  • I cleaned up any pre-built binaries.
  • I ran simulation/ship_landing_cop_prep.sh and it built the various files, including the Copter and Rover SITL binaries.
  • I ran simulation/ship_landing_cop_start.sh and it launched the Gazebo simulation.
  • I ran $SITL_MODELS_DIR/Gazebo/launch/mavproxy-multi-vehicle.sh 5 --console and it opened MAVProxy.
  • I start a diamond-shaped mission on the 2nd truck (SYSID=4).
  • In MAVProxy, in vehicle 1 (copter):
set fwdpos 1 # Enable position forwarding
param set FOLL_SYSID 3 # Target trailer 1
param set SHIP_ENABLE 1 # Enable the ship landing functionality
param set SHIP_OFS_Z 20 # Set the landing approach altitude
param set SHIP_AUTO_OFS 1 # Calibrate the trailer offsets
  • mode guided; arm throttle; takeoff 40 The copter takes off without issue.
  • mode rtl The copter approaches trailer 2 but hovers over it at 17m and slightly behind it.

Here is one more pictures of the landing lag:
Screenshot from 2023-10-10 21-37-55

@Georacer
Copy link
Contributor

With a quick scan of the codebase I understand that the parameter PLND_XY_DIST_MAX is only used in Copeter and not in QuadPlane? And the same goes for the landing logic that uses it (i.e. ArduCopter/mode.cpp::land_run_vertical_control()).

This has me worried a bit, on whether the actual precision landing performance in Copter will be as good as the equivalent in QuadPlane.

@KosmX
Copy link
Author

KosmX commented Oct 12, 2023

WPNAV_RADIUS shouldn't be too high, (probably 10 to 50m) if the copter is just too far behind, you may need to increase FOLL_POS_P.

PLND_TYPE=5 is the primary reason for this PR, it allows precision landing to follow a script.
precland should fix for the moving platform, if that doesn't happen, check if PLND_EST_TYPE is 1 (Kálmán filter)
If that's not the case, precland won't be able to estimate movement.

If there is too much lag in FOLL phase, try setting FOLL_POS_P to a higher value.
WPNAV_RADIUS shouldn't be too high (i think it should be somewhere around 10-50m at most)


Disarm: that didn't really work for me either when testing in simulation, but I think it should work IRL (based on some testing)


QuadPlane and Copter code contol logic is different, copying code won't work..

@Georacer
Copy link
Contributor

Georacer commented Oct 21, 2023

Hi again! Sorry for the delayed answer.

I don't think FOLL_POS_P is the issue. My problems are in LAND mode, not in FOLLOW mode.

PLND_EST_TYPE is 1 (Kalman), as you said.

I have set WPNAV_RADIUS to values from 100 to 500cm. No success.

The copter keeps lagging at ~4.3m behind the landing point, which is more than the default PLND_XY_DIST_MAX, hence the UA does not descend. If I relax PLND_XY_DIST_MAX to, say, 5m, the landing continues and completes. But with 4.3m offset, of course.

Conclusion: Still not successful with reproducing this PR.
Here is my parameter file: copter_params_gh_issue.txt

I might try a real-world effort, to rule out simulation numerical issues. Let me know if I can help with more information.

P.S. I'm using the ship landing script you sent via the .tar.gz and not the one from the PR. But I don't think there will be much difference, right?

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

2 participants