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

Sub: support ABOVE_TERRAIN frame in GUIDED mode posvel case #27767

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

Conversation

clydemcqueen
Copy link
Contributor

Sub Guided_PosVel mode currently assumes Location::AltFrame::ABOVE_ORIGIN. This PR adds support for Location::AltFrame::ABOVE_TERRAIN.

This new functionality is exposed two ways:

  • Using MAVLink: SET_TARGET_POSITION_GLOBAL_INT.frame = MAV_FRAME_GLOBAL_TERRAIN_ALT_INT
  • Using Lua: set_target_posvel_terrain(Vector3f, Vector3f)

The motivation is to allow the development of scripts that drive the ROV at a constant xy velocity and at a constant height above the seafloor, while giving the pilot control over heading. There's a new autotest that demonstrates this.

Possible open issues / future PRs:

  • Is it better to add an optional frame parameter to the set_target_posvel_NED(Vector3f, Vector3f) Lua binding?
  • Sub Guided_WP mode could also support Location::AltFrame::ABOVE_TERRAIN, though this mode does not support rapid target updates

@timtuxworth
Copy link
Contributor

timtuxworth commented Aug 22, 2024

Very interesting I'm working on something similar for Plane. Here's my draft PR for plane #27909

@clydemcqueen
Copy link
Contributor Author

@timtuxworth Thanks for reaching out! I will read your PR and try to stay in sync where I can.

My use case doesn't depend on a GCS, instead I am using a Lua script to send targets at 10Hz. This allows the sub pilot to control heading while GUIDED mode handles the xyz motion. Here is the script that I am testing: https://github.com/clydemcqueen/ardusub_surftrak/blob/guided_above_terrain/lua/transect.lua

@@ -178,6 +178,7 @@ struct PACKED log_GuidedTarget {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t type;
uint8_t alt_frame;
Copy link
Contributor

Choose a reason for hiding this comment

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

Have you thought about making this a Location::AltFrame instead of uint8_t?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Hmmm, will all compilers map Location::AltFrame to uint8_t? I don't see this usage anywhere else in the code.

@clydemcqueen
Copy link
Contributor Author

We tested this w/ an A50 DVL off Seattle's Pier 62 on 21-Aug-2024 with good success. Learnings:

  • We forgot to set WPNAV_ACCEL_Z to to match PILOT_ACCEL_Z, so we had some strong up/down oscillation due to sonar delay. (SURFTRAK performed as expected since it uses PILOT_ACCEL_Z).
  • We learned that the lower limit for WPNAV_SPEED is 20 cm/s, vs the desired 10 cm/s. This has now been changed in master.
  • The script tried to set the target position even when the rangefinder was unhealthy, resulting in a bunch of warnings in the GCS. (It looks like mavlink-router drops some messages, so the rangefinder is unhealthy more often than I expected, see ArduSub timeouts when rangefinder value > 2.5m bluerobotics/BlueOS-Water-Linked-DVL#44.) I updated the script to avoid generating warnings.

We will test again in a few weeks.

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.

2 participants