srmainwaring / asv_wave_sim

This package contains plugins that support the simulation of waves and surface vessels in Gazebo.
GNU General Public License v3.0
114 stars 31 forks source link

Water patch is too small #9

Closed lopsided98 closed 1 year ago

lopsided98 commented 3 years ago

I saw your posts on the ArduPilot sailboat thread, and have been trying out this project. It's definitely the best sailboat simulator I've found, so thank you for the work you put into it.

One issue I have been running into is when the boat capsizes due to too much wind, the simulator stops working and prints the following error thousands of times:

[Err] [WavefieldSampler.cc:207] Water patch is too small
[Err] [WavefieldSampler.cc:205] point:  1.03388e+253 -1.19529e+252 -5.06649e+252

I've been working on modeling my own boat, and it happens even more with it. If I add the rudder to the URDF, it happens immediately on startup.

In https://github.com/srmainwaring/asv_wave_sim/issues/8 you mentioned that you had a fix, but that doesn't seem to be published.

Interestingly, I switched to a debug build to try to look into the problem more, and the error changed:

terminate called after throwing an instance of 'CGAL::Precondition_exception'
  what():  CGAL ERROR: precondition violation!
Expr: ! K().collinear_3_object()(p,q,r)
File: /nix/store/4pd2d8rrzy6x4v08hzw713iq28wvkssw-cgal-5.1/include/CGAL/Kernel/function_objects.h
Line: 1780
srmainwaring commented 3 years ago

@lopsided98 thanks for your words of support. I have not pushed the changes back into master as they are part of a wider set of changes included in one of the branches.

If you try the branch used in the ArduPilot POC:

https://github.com/srmainwaring/asv_wave_sim/tree/feature/ardupilot_sailboat_poc

the simulation should continue when the boat capsizes. As well as the enlarging the water patch this version uses FFTs to generate the wave field and tiles the ocean providing a larger area to sail in. Unfortunately I have not completed the services to set the environment parameters at runtime, but if this is of use to you I can bump this up my list of priorities.

The issue with your rudder may be more subtle. If the mesh has degenerate triangles there may be errors. I supply two meshes for the objects subject to buoyancy forces: one is for the visual and this doesn't need to be modified, the other is for the collision and it helps to simplify this and ensure the triangular mesh is well formed and has fewer vertices. I use Blender and the decimate modifier to process the collision meshes.

lopsided98 commented 3 years ago

I am using the ArduPilot POC branch. I can reproduce the issue by turning up gravity so high the boat sinks, or turning up with wind to an extreme amount.

I've been looking into it some more and I think the water patch issue may not be the root cause. It looks like some part of the pressure drag calculation is generating huge forces (>10^18) which launch the boat off the map. As the floating point coordinates start getting really large, other parts of the code break. Turning off pressure drag eliminates the issue. It looks like the debug configuration enables extra assertions in CGAL, and changes the location of the crash by making CGAL complain about a collinear triangle while calculating normals.

I think you are right that there is something wrong with my mesh. When the CGAL assertions are enabled, it complains on startup that there is a collinear triangle (it does this even without the rudder). I am already using the Blender decimate modifier to generate my collision meshes from my CAD model, but there is still obviously something wrong somewhere.

lopsided98 commented 3 years ago

I fiddled with the meshes in Blender, and was able to get it to start without crashing. As soon as I add more than a little wind though, something goes wrong and it crashes (due to huge forces launching the boat). With the RS750, I found I can reproduce the problem reliably with a 4000000 Nm torque around the x-axis (that sounds absurdly large, but it is only applied for one iteration and should just flip the boat once or twice). I have found that I am able to reproduce the problem even with all drag forces disabled.

My boat is still using the scaled up RS750 sails despite being only 1 meter long, so that might be making the bug easier to trigger. I will work on modeling the real sails to see if it makes it more usable, but I'd really like to figure out the root cause.

srmainwaring commented 3 years ago

I haven't stressed the calculations with large forces to the extent that you have, so that's something I'll need to look into. From what you describe It should be independent of the wave field - so a simpler generator may be easier to investigate. The overflows should also occur for simple shapes like a box which are much easier to analyse.

I can look at the mesh for your boat and try to replicate the issue if you're happy to share it. I had to manually edit the collision mesh for the RS750 to eliminate stray vertices etc. where the hull joined the desk and other areas with high detail / vertex density.

lopsided98 commented 3 years ago

I still haven't figured out the root cause, but I have managed to get my boat to work under normal conditions (it still seems a little more prone to crash than the RS750, but it is usable) by reducing the configured area of the keel fin and rudder to their correct values (rather than those of the RS750). If you want to look more into it in the future, I'll let you know when I put my boat's model on GitHub.

This is getting a little off topic, but do you know of any good way of estimating the foil parameters? I looked at using XFLR5/XFOIL, but the method they use seems to not be valid at large angles of attack, which is a common situation for both the sails and the rudder. I'm thinking of looking into OpenFOAM, but I think I'd have to learn quite a bit more about fluid dynamics first.

srmainwaring commented 3 years ago

@lopsided98 glad to hear you've managed to get a model working with the simulation.

I'm afraid I haven't had a chance to investigate the wave simulation in detail yet but would like to understand the cause of the problems you are seeing. I've been busy getting another sailing vehicle working with Ardupilot - a land yacht which has simpler physics to simulate but different tuning issues for a physical vehicle.

My approach to fitting foil parameters is fairly crude, but seems to work well enough for the simulation to capture the main vehicle characteristics in the examples I've applied it. I've attached a spreadsheet used to estimate parameters for a wing sail foil used in the land yacht. The starting point is to find a profile on http://airfoiltools.com that approximates your foils and work from there. Given the heroic approximations used in the Gazebo foil plugins I don't think a lot is gained by searching for a perfect fit.

land_yacht_aerodynamics.xlsx

RobinBaruffa commented 3 years ago

I had the same problem after connecting a rudder to a custom boat, I would get the same error

[Err] [WavefieldSampler.cc:207] Water patch is too small [Err] [WavefieldSampler.cc:205] point: 1.03388e+253 -1.19529e+252 -5.06649e+252

I troubleshot it by advancing step by step in Gazebo. I had specified a max and min angles for the rudder joint, and when the rudder went beyond the maximum angles, the physics engine would apply a very high torque only during a couple of iterations in order to satisfy the max angle constraint. That, coupled with a way too small inertia matrix for the rudder link led to a very fast displacement of the rudder, causing the lift drag computation to generate huge forces.

srmainwaring commented 3 years ago

@RobinBaruffa that's interesting - so it may that be the velocity dependent drag forces are the source of the issue rather than the buoyancy calculation. We could add an upper bound to the damping to prevent the forces from getting out of hand.

RobinBaruffa commented 3 years ago

Yes but in my case adding an upper bound to prevent the forces from diverging would not have solved the problem because the physics engine would have kept messing with the rudder's velocity. In my case, the problem didn't come from the LiftDragPlugin but from a personal error in design, the rudder joint shouldn't go beyond its limits and I think it should be the user's responsibility to keep it that way by having a proper joint control that satisfies this constraint, rather than relying on the physics engine collision.

It could also be possible of averaging the velocity measurements over a certain amount of iterations to filter out the physics engine collision induced velocity spike.

RobinBaruffa commented 3 years ago

I'm also getting of topic but I'm planning on adding support for water currents for the HydrodynamicsPlugin and the LiftDragModel. I will use the same approach as the one in the _usv_sim_lsa_ project (a paper is available here), with a ros topic that publishes a non-uniform water current vector field.

LFS-Robotics commented 1 year ago

Has there been any update with this? I am using the gazebo11 branch using ROS Noetic and have a simple 3D model of a big boat. No moving parts or joints. I just want it to float and interact with the waves but no matter how small I make the model and how much I seem to change the damping. I am just getting the map error of water patch is to small, and the point values changing a lot. Any suggestions on how to get around this?

srmainwaring commented 1 year ago

The size of the patch is set using the mesh AABB here:

https://github.com/srmainwaring/asv_wave_sim/blob/62ffdcfd2eec6d2f80d834606d96a6b828008e03/asv_wave_sim_gazebo_plugins/src/HydrodynamicsPlugin.cc#L645-L655

In the Gazebo Garden version there are some issues dimensioning this automatically I didn't realise it was still an issue on the legacy version. Have you managed to get the example models working? The WAM-V works as this was the floating body I used to test the ROS Noetic port.

There may also be some issues with the mesh you are using (unless you are using a collection of primitives). If you can supply the basic mesh I can investigate.

LFS-Robotics commented 1 year ago

The size of the patch is set using the mesh AABB here:

https://github.com/srmainwaring/asv_wave_sim/blob/62ffdcfd2eec6d2f80d834606d96a6b828008e03/asv_wave_sim_gazebo_plugins/src/HydrodynamicsPlugin.cc#L645-L655

In the Gazebo Garden version there are some issues dimensioning this automatically I didn't realise it was still an issue on the legacy version. Have you managed to get the example models working? The WAM-V works as this was the floating body I used to test the ROS Noetic port.

There may also be some issues with the mesh you are using (unless you are using a collection of primitives). If you can supply the basic mesh I can investigate.

Yes all the example work (Except from the Barrage Buoy, which just sinks). The map size should be fine the model is about the size of the buoy (as its scaled down). But the point output error is showing the position going all over the place. Jumping from - 1000 to about 2300 in all 3 parts. Unfortunately I cant share he model due to its purchase license. All I want to be able to do is to have the boat move up and down and side to side with the waves so that i can test simulated sensor outputs from onboard the model. Do you have any suggestions of things to look for, or things to change in code to try and solve this?

srmainwaring commented 1 year ago

The barrage buoy sinks because the plugin is attached to the composite (barrage) rather than the individual element (barrage buoy) - so there is nothing odd going on there.

It may the mesh you are using. Are you using the mesh for the boat visual? Generally a visual mesh will have many thousands of vertices, may not even be triangulated if the CAD system outputs quads, and could be quite ill conditioned (so triangles that have co-linear points). Getting a good collision mesh requires some work in Blender or similar to simplify the mesh. The physics calculations are not bullet-proofed against a bad mesh and this could lead to an overflow => large forces. Hard to say precisely without being able to run an example.

To see the difference between the visual and collision meshes compare wam-v-base_collision.stl to wam-v-base.stl. The collision mesh has the fine detail removed and has the mesh decimated (and may have been subsequently re-meshed to improve the triangulation).

You can synthesise your boat's shape using a collection of primitives for the collisions (I think that the legacy version will apply buoyancy to all collisions in a link element - will need to check). Clearly not as clean as using a single mesh, but you can block out the shape using a number of boxes to get indicative behaviour before doing the mesh work - if indeed that turns out to be the problem.

Edit here's a link to some slides I presented at a Gazebo community meeting that discuss the meshing requirements in more detail.

LFS-Robotics commented 1 year ago

The barrage buoy sinks because the plugin is attached to the composite (barrage) rather than the individual element (barrage buoy) - so there is nothing odd going on there.

It may the mesh you are using. Are you using the mesh for the boat visual? Generally a visual mesh will have many thousands of vertices, may not even be triangulated if the CAD system outputs quads, and could be quite ill conditioned (so triangles that have co-linear points). Getting a good collision mesh requires some work in Blender or similar to simplify the mesh. The physics calculations are not bullet-proofed against a bad mesh and this could lead to an overflow => large forces. Hard to say precisely without being able to run an example.

To see the difference between the visual and collision meshes compare wam-v-base_collision.stl to wam-v-base.stl. The collision mesh has the fine detail removed and has the mesh decimated (and may have been subsequently re-meshed to improve the triangulation).

You can synthesise your boat's shape using a collection of primitives for the collisions (I think that the legacy version will apply buoyancy to all collisions in a link element - will need to check). Clearly not as clean as using a single mesh, but you can block out the shape using a number of boxes to get indicative behaviour before doing the mesh work - if indeed that turns out to be the problem.

Edit here's a link to some slides I presented at a Gazebo community meeting that discuss the meshing requirements in more detail.

I agree it does seem to just be the mesh. I took the collision field out and replaced it with the collision for the box model and it now floats. I will just change the box dimensions to roughly be the same as the bottom of the boat and that should work okay for me. thanks for your help.