Sailboat Support

I have taken my sailboat out twice now, it is improving each time, but I have a question for the experienced in the group.

My boat was getting stuck head-to-wind in the light wind sometimes, which is fine, but I had the rudder servo PWM on mission planner and noticed that sometimes the rudder would go from holding hard over at 1100 then jump the opposite way, 1900 for a second or less, then back to 1100. This usually kept it stuck in irons longer than needed.

I assumed it was due to the GPS velocity showing the boat going in reverse and it reversing the rudder as Iā€™ve seen that in the code. But on analyzing the data I donā€™t see the GPS heading change in most of these cases.

It might just be that the telemetry log misses a short term change (my dataflash did not work on this test) but I thought I would see what other causes could be and what else to check in the data.

Hereā€™s a plot with some markups of what I see, and a link to video

Thank you!

You have it tracked down, the boat thinks its going backwards.

Were not navigating directly based on the GPS data, we fuse it into the EKF. So I guess if you were to plot the EKF north and east velocity you would see the reversal there.

I think I have a branch somewhere that gives you the option to just turn off reversing the rudder when going backwards, of course that is very bad if you are actually going backwards but constant reversing of the rudder is quite bad if your just trying to drift it round a tack.

Maybe we could add some hysteresis on the reversal and get the best of both.

Thanks for the quick response! I will check the EKF velocity components in future tests if I see this again.

I think it might be useful to be able to turn off reverse reversing, not for this case, but here on SF bay where I hope to send the boat, the currents are strong and often the boat could be sailing forward through the water but moving backwards over the ground.

The current code will cause the boat to circle downstream rather than fight the treadmill. That case is a losing battle either way, and no way to tell what is going on without speed through the water sensors, so I will leave it to you developers to decide what is most important.

I have no idea what would happen in that case, defiantly worth doing some careful testing first.

Plane can estimate the wind speed from the difference between the ground speed vector and the heading, its not enabled on rover, but it should be possible to get it to work in the same way. Then we can do the right thing in that case. Its much harder on sailboats just because the speed if typically much closer to the noise floor of the GPS.

Iā€™m reading through Rover/sailboat.cpp and I come across this comment:

// wing sails auto trim, we only need to reduce power if we are tipping over

It appears from the following code that the elevator goes full left or full right in normal sailing (when not trying to depower to reduce heel or to center when motoring). Is my understanding correct? I imagine that the actual deflection is set through SERVOx_MIN/MAX parameters.

How does this work for sailing downwind? Is it impossible to use wing-and-elevator setup as a drag device, i.e. if the wind is directly behind, turn the wing chord at 90 degrees to the hull? Will the wing still fly at an acute angle to the apparent wind even if itā€™s directly from behind?

Yes, that is correct.

Also yes, you cant do drag with a ā€˜elevatorā€™ actuator. You could have stoppers to it canā€™t swing round too far. We could also add support to a directly actuated wing.

Thank you, Peter. Iā€™m back to working on my wing sail project, and Iā€™m just learning the code. The stops make perfect sense for an elevator sail.

You remember my project! Iā€™m flattered.

It looks like the code would be fairly straightforward. I would add a new argument, &dd_sail_out, to Sailboat::get_throttle_and_mainsail_out and a new SERVOx_FUNCTION, something like ā€œdirect drive wing sail.ā€ This would be consistent with 89: Main Sail and 128: Wing Sail Elevator, although I worry about breeding obscure servo functions. Another way would be to keep one servo function, and have an enumerated parameter for sail control type, where 1 would be traditional winch; 2, elevator wing sail; 3, direct drive; etc.

Let me know which approach you prefer and Iā€™ll start a branch.

I made a placeholder PR: https://github.com/ArduPilot/ardupilot/pull/17065

Let me know if Iā€™m in the right direction.

Hi there,

I found this ultrasonic wind sensor pretty cheap. 69ā‚¬:
https://your-smarthome.com/shop/netatmo-smarter-windmesser-zusatzmodul-fuer-wetterstation-windsensor-zeigt-gefuehlte-temperatur-an
It is connected to a base station with 868MHz. Do you think, there is a chance, to modify this kind of sensor, to use without the base station? Wireless would be nice to have, but I would prefere a wired connection,
Should I give it a try?
Happy sailingā€¦

I would guess that would take some none-trivial reverse engineering. Its not going to be plug and play.

My boat is working pretty well! Just one frustrating thing: the boat reliably starts a tack, then tacks back head-to-wind, then usually tacks again to finish the tack.

You can see this in the track image (wind is coming from the south, bottom of the image, shown with the yellow arrow). Each tack has an S turn in it.

Also see the video, the video starts when the boat is about at x=15, y=0 in the track plot.

The plot vs time shows that the turn is commanded, the yaw-rate command changes sign and the boat follows suit. So it is intentional, but confusing, and I wonder if anyone can explain it.

I have two ideas:

One idea is that this is an overshoot of a heading command, that the boat turns quicker than the controller is planning, so it turns back. I donā€™t have a heading command in my data so canā€™t tell if this is a possible mode or not. Does the heading command slowly change or is it a step change for the tack? If itā€™s a step change then I donā€™t think this is the issue.

Another idea is that since my windvane is off the back of the boat, as the boat yaws the windvane gets a component from the rotation. You can see the wind direction change during the tack, but it also changes on each leg due to the apparent wind component so Iā€™m not sure if this is it. Once the tack is complete it would turn to follow the vane and this could cause it to tack back if the windvane is incorrect.

Track:

Plot vs. Time:

Nice! Looks like its going well apart from the double tacking. Can you share the log?

I didnā€™t have an SD card in for this test, oops.

Here is a link to the telemetry data and my matlab script to analyze it, if that helps.

Nothing fantastically conclusive, a log from the SD card has a little more info in.

I would recommend updating to the new 4.1 beta (should be out in the next few hours). There are some improvements that will hopefully fix / help with your tacking issues.

I have seen it before due to a sticky wind-vane, it would be stuck on the old tack so the tack would never be completed, probably made slightly worse in your case as its shadowed by the sail as it goes through the tack. Once you have a bit stronger wind the windvane stays pointing into the wind for the whole tack and the code does not get as confused.

Maybe if we logged the pre-filtered apparent wind direction straight off the sensor it would make sticky sensors easier to diagnose.

Iā€™ll update and give it a try, with an SD card. My vane is really low friction so I know it isnā€™t stuck, but it seems like it could be error in the measurement through the tack.

I was considering compiling a version of the code that takes out finishing the tack by being within 10 degrees of the new heading, so that it always takes 5 seconds to get on the new tack, this would give a little time to get to the new steady state measurement. Eliminate the first test below and it will fall through to the 5 seconds, what do you think?

if (fabsf(wrap_PI(tack_heading_rad - rover.ahrs.yaw)) <= radians(SAILBOAT_TACKING_ACCURACY_DEG)) {
    clear_tack();
} else if ((now - auto_tack_start_ms) > SAILBOAT_AUTO_TACKING_TIMEOUT_MS) {
    // tack has taken too long
    if ((motor_state == UseMotor::USE_MOTOR_ASSIST) && (now - auto_tack_start_ms) < (3.0f * SAILBOAT_AUTO_TACKING_TIMEOUT_MS)) {
        // if we have throttle available use it for another two time periods to get the tack done
        tack_assist = true;
    } else {
        gcs().send_text(MAV_SEVERITY_INFO, "Sailboat: Tacking timed out");
        clear_tack();
    }
}

Thanks for the help!

I would update the the latest version before getting into code changes but your more than welcome to get stuck in.

It could also be a weight imbalance in the vane such that it tends point up when the heeling over. SD card logs will have the apparent wind (so will a Tlog on 4.1) so we might be able to better tell what is going on.

I have done abit of a re-work of the windwane code. The main change is to store apparent wind direction in body frame so yaw/compass issues should not mess up the reading. It also improves the filtering and adds more logging so it should now be much easier to track down issues.

This is the PR.

Happy to do build firmware if anyone fancyā€™s giving it a try.

2 Likes

Thanks Peter - looks good. Iā€™ll be interested to see if this helps with the issue I was having with the land yacht attempting a second tack on exiting a waypoint.

Btw there were a couple of other sailing PRs in progress - one to do with the wing sail PID controller and another with the max g-force on the nav controller. Do you need any help getting those tested and merged?

I will try the rework out. I cloned your fork, then checked out this branch and compiled it, does that sound right? My github skills are rudimentary. Branch I compiled:

https://github.com/IamPete1/ardupilot/tree/windvane-rework

I have bench tested it. I did notice that ā€œWind Directionā€ on the telemetry is now stuck at 0.0 where before it was a compass heading. The apparent wind is showing up just fine. I see that in the log too. Maybe because I donā€™t have a wind speed sensor?

Update on my boat:
I did a couple of tests with the beta version (not this update) last week to see if it would solve my double-tack issue, and it did not. I also tried a version where I force the tack to time-out (see my previous post) to hopefully get past any transients that might be confusing it while turning. That did help, but it still double-tacked occasionally. Maybe extending the timeout to more than 5 seconds would be better. Iā€™m hoping some analysis of the vane and guidance data can tell more and find a less hacky fix. Unfortunately my dataflash logs havenā€™t worked yet. The bench test of the windvane-rework branch did give a good log file, hopefully I can get on the water later this week.

I made a longer video of my first tests you can see here

Your right, I had not tested having direction only, I have just pushed a fix.

Would be nice to get your logging working, I think that is the key to understand the double tack your seeing. First thing would be to format the card, then it is worth setting some slow down with BRD_SD_SLOWDOWN maybe try 20.