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

Rover: Direct-rotation sail control #17066

Merged
merged 4 commits into from Apr 28, 2021

Conversation

arikrupnik
Copy link
Contributor

@arikrupnik arikrupnik commented Mar 31, 2021

Allows a sailboat configuration where a servo directly rotates the mast, rather than controlling its AoA indirectly with a sheet or an elevator-like surface.

Rover/AP_MotorsUGV.cpp Outdated Show resolved Hide resolved
@IamPete1
Copy link
Member

looks good so far, just need the the magic function to set it.

You will also need to add it to get_pilot_desired_mainsail

This is slightly more complex than the existing outputs, they both have a fixed position to de-power. You will have to actively drive this to point into the wind to de-power. You might have to add some code paths for this, get_stop_sail or something, can just return 0 for the two existing outputs.

@arikrupnik
Copy link
Contributor Author

Thank you for pointing out get_pilot_desired_mainsail. I'm not sure what it represents. Is it the servo position that the operator would request if the boat were in manual mode? In this case, I think it's exactly as wingsail_out, both in the absence of the input and in its presence. Forcing mast_rotation to 0.0f would orient the sail parallel to the hull. This is as close to completely depowering as there is. Reaching wind would heel the boat without making any headway, and headwind would push her backwards only as much as the sail's Cd. I think actively driving the sail to point into the wind can reduce heel (and leeway), but would allow headway to the extent that the alignment with wind is imperfect. Perfect alignment with keel guarantees zero headway.

@IamPete1
Copy link
Member

Thank you for pointing out get_pilot_desired_mainsail. I'm not sure what it represents. Is it the servo position that the operator would request if the boat were in manual mode?

Excatly.

I'm not sure about just fixing the wing to parallel to the hull, I think your just going to get knocked about with excessive heel. It also means you have to go via a high angle of attack to get to a lower one, so setting off and stopping might get quite exciting. I also don't think you would actually stop, I suspect you might just end still going forward a bit and slipping sideways alot.

Feel free to try it IRL and prove me wrong, we can always add pointing the wing into the wind as a future improvement.

@arikrupnik
Copy link
Contributor Author

I can try to take some videos that show this. I'm still waiting for my wind vane, but this is something I can demonstrate under manual control. I have the sail control on a knob on my TX, so that rotating the knob clockwise rotates the mast clockwise. Middle detent on the knob is the "off" position for this sail.

Mind you, with a sail winch, sheeting all the way out depowers you only in as much as you're going upwind. If the wind happens to be from behind, you'll get all the power :=) The future improvement you speak of could actively manage the sail angle for mast rotation and for the winch. Sort of the opposite of what the comments call "ideal angle" for the winch.

Outside of that, is there anything else I'm forgetting before I get to the magic? (it's not actually that magical, but I do need the hardware).

@IamPete1
Copy link
Member

IamPete1 commented Apr 1, 2021

Outside of that, is there anything else I'm forgetting before I get to the magic? (it's not actually that magical, but I do need the hardware).

Its looking good. Just need the extra few lines ;). I suspect you will have to add a offset param. We could assume that the servo range is mapped -180 to +180 relative to the hull, then just add a offset param to remove the need to do that mechanically. Should be able to re-use the ideal sail angle param to set the sail relative to the wing to go forwards (and backwards).

Rover/AP_MotorsUGV.h Outdated Show resolved Hide resolved
@arikrupnik
Copy link
Contributor Author

Thank you for your encouragement, Peter.

I'm not sure I understand fully your meaning about the offset parameter. Are you talking about constraining the range of rotation or setting the middle point? I would have thought you can control both with SERVOx_MIN/MAX/TRIM parameters.

I'm planning to use SAIL_ANGLE_IDEAL like you suggest, and SAIL_ANGLE_MAX to map SERVOx_MIN/MAX to degrees of rotation. On my boat the geometry works out so the sail can rotate only about +-85 degrees. You never need to rotate more than +-90 degrees, even if you want to go backwards. I really wasn't panning on having the boat reverse, but if you really want to, you simply put the sail sharp edge into the wind--it works better than you might expect; the only major downside is the sharper stall. I'm planning to ignore SAIL_ANGLE_MIN.

The ideal angle applies when sailing upwind. It is the AoA that gives best L/D ratio, 10-12 degrees. When running, you use the wing as a drag device and turn it to present the widest area, more or less 90 degrees to the wind. There is a discontinuity when going from one mode to the other, and another when jibing: as the boat jibes from starboard to port tack, the sail needs to rotate 180 degrees to keep the leading edge into the wind. I'm not yet sure how to handle that--probably with some kind of hysteresis.

@rmackay9
Copy link
Contributor

rmackay9 commented Apr 1, 2021

nice to see this additional support in sailboats. @IamPete1 is the maintainer so I leave the decision to him but I wonder if we need sparate main_sheet and mast_rotation values. I guess there's no way we could squash them together?

@arikrupnik
Copy link
Contributor Author

@rmackay9 There was some discussion about that here: https://discuss.ardupilot.org/t/sailboat-support/32060/767

There are two sail control output types in master, this PR is proposing a third. It is unlikely that the same boat would have different types of control, even it she has multiple sails. The alternative is to have one output type, and a new parameter that would control which type of sail control the boat has. Maybe even make SAIL_ENABLE an enumeration, where 0 would mean disable, 1 would mean winch, 2 would be wing-with-elevator and 3 would be direct rotation control.

@rmackay9
Copy link
Contributor

rmackay9 commented Apr 1, 2021

@arikrupnik,

Yes, I can imagine it's a choice between a servo function and a type parameter... adding a servo function is probably closer to what we are doing for other methods of control.

@arikrupnik
Copy link
Contributor Author

I made a new parameter, SAIL_WNDVN_ROTATES. First, please tell me if I did this right, I probably missed some aspect of parameter definition. Second, I wasn't sure if it should go under sailboat or windvane parameters. I put it under sail, since this is the only class that can use it, seeing as no other frame has rotating masts. I can move it if it makes more sense in the other place.

The purpose of this parameter is to accommodate the use case, like my MaxiMOOP, where the vane is mounted on top of the mast and the mast rotates. In this case, the code must subtract mast rotation angle from vane reading to compute apparent wind angle. This is possible both with winch and direct-control masts, as in both cases the code attempts to set the angle of the sail.

To perform the computation, I must read the previous value of the sail servo, before the running code requests a new setting. I'm not sure how to accomplish that--perhaps @IamPete1 or @rmackay9 can point me to an example.

Rover/sailboat.cpp Outdated Show resolved Hide resolved
@arikrupnik
Copy link
Contributor Author

arikrupnik commented Apr 5, 2021

My vane arrived and found a temporary place on the boat that doesn't need to know mast rotation to work. It looks funny, especially with the small sail, but it's functional. It appeals to my laziness: I simply cut a piece off the stock mount and drilled it to fit my mast step rails.

20210405_173735
20210405_173424

@arikrupnik arikrupnik force-pushed the direct-sail-control branch 2 times, most recently from e27a646 to fe6725b Compare April 11, 2021 04:26
@arikrupnik arikrupnik changed the title WIP: Direct-rotation sail control Rover: Direct-rotation sail control Apr 15, 2021
Rover/sailboat.cpp Outdated Show resolved Hide resolved
Rover/sailboat.cpp Outdated Show resolved Hide resolved
Rover/sailboat.cpp Outdated Show resolved Hide resolved
Rover/sailboat.cpp Outdated Show resolved Hide resolved
Rover/sailboat.cpp Outdated Show resolved Hide resolved
@arikrupnik
Copy link
Contributor Author

Took off the last commit based on feedback from @IamPete1 on discord.

Rover/sailboat.cpp Outdated Show resolved Hide resolved
Rover/sailboat.cpp Outdated Show resolved Hide resolved
@arikrupnik arikrupnik force-pushed the direct-sail-control branch 2 times, most recently from 8a509f3 to 63bc0c1 Compare April 27, 2021 19:23
Copy link
Member

@IamPete1 IamPete1 left a comment

Choose a reason for hiding this comment

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

Looks good to me, thanks for putting up with all the change requests!

@IamPete1 IamPete1 merged commit 3bea2fd into ArduPilot:master Apr 28, 2021
@arikrupnik
Copy link
Contributor Author

Looks good to me, thanks for putting up with all the change requests!

Thank you for guiding me through a first-time PR process.

@Hwurzburg Hwurzburg added the WikiNeeded needs wiki update label Apr 29, 2021
@Hwurzburg Hwurzburg removed the WikiNeeded needs wiki update label May 31, 2021
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.

None yet

4 participants