Replies: 2 comments 2 replies
-
|
This is a great question!
Most of the parameters (including hydrodynamic parameters) used in the examples are based on Chu-Jou's thesis that you have linked.
The general answer to most of your questions here is that the matrix values themselves should be consistent (assuming a 45-degree mounting orientation), but - as you have seen - the signs can vary depending on an individual's hardware configuration, choice of body frame, and thruster interface. For example, someone's ESC wiring could be reversed, resulting in a sign mismatch (more on this below). I would recommend that you follow a procedure similar to the following:
To answer some of your more specific questions,
The examples in this repository all use FRD. In practice, I personally have started using FLU to avoid friction with other ROS packages.
I had not seen that link. Thank you for sharing 😄 I would be happy to update things to be consistent with it to avoid confusion in the future.
The TAM used in simulation is a mess - don't use that as a reference for your hardware!
The nuance here stems from how the forces requested by the TAM are applied by the thrusters. To elaborate, there are two main ways that we can control the direction of the propellers in order to match what is defined as forward thrust: (1) we can change the signs in the TAM or (2) we can configure the thruster controllers to use a different thrust curve. The current implementation of the thruster controllers makes it easier to modify the TAM, which is why I recommend that. Below are the configurations that I am actively using in our own hardware deployments (click dropdown) |
Beta Was this translation helpful? Give feedback.
-
Very cool. Do you like the Navigator interface? Replacing ArduSub and MAVROS with the Navigator interface has been on my backlog for quite some time.
Ha! I am a victim of my own crime.
I agree with this opinion, and I like your idea regarding removing this responsibility from the TAM. I have submitted a PR that implements your idea here: Robotic-Decision-Making-Lab/auv_controllers#84 Let me know what you think.
I'll give it a read. Thank you for sharing! Best of luck with your writing and defense. |
Beta Was this translation helpful? Give feedback.
Uh oh!
There was an error while loading. Please reload this page.
-
Hi Evan,
I am currently working on my Master’s thesis, where the main contribution is the integration of a local path planning framework for the BlueROV2 Heavy. As part of this work, we switched from ArduSub to your ll-control framework using the demos in the auv_controllers repository. This has allowed us to directly use our own state estimation and significantly simplified debugging compared to the ArduSub controllers. Thank you for making it accessible :).
I have a few questions on the thruster allocation matrix (TAM) you have implemented in the control demos in the blue repository
blue/blue_demos/control_integration/config/bluerov2_heavy_controllers.yaml
Lines 77 to 83 in 812fea6
as well as in the auv_controllers repository
https://github.com/Robotic-Decision-Making-Lab/auv_controllers/blob/9ac9ebaa8d32184886542be0441f47302c31641d/auv_control_demos/chained_controllers/config/chained_controllers.yaml#L98-L104
Do you still remember the source of this TAM?
I have seen the open issue about the TAM here: #97
However, the "Simulated TAM" you posted in this response is not the same as the one in the control demos linked at the top of this post.
Therefore, I have some questions on the definitions used in the setup of the TAM as well as the thruster_allocation_matrix_controller using it:
Frame definitions
Am I correct in assuming that you are using the body-axis aligned frame (Front, Right, Down)?
Forward Thrust Direction
In issue 97 you sepecify that you assume "forward" direction of thrust to be the case when the thruster pushes water TOWARDS the cable. Is that still true?
I am not trying to say that you have to follow this, but I am wondering if you have seen the definition of Blue Robotics on "forward" thrust direction: They seem to define the forward thrust direction in case the propeller pushes water FROM the side with the cable to the other side (https://bluerobotics.com/learn/thruster-usage-guide/#introduction, see section Thruster Direction).
Looking at the hardware and simulated TAMs in discussion on issue 97, you seem to incorporate the direction of rotation of the propeller in the TAM as well (contribution of thruster 5 in z is negative while thruster 6 is positive, while they are mounted in the direction while having propellers that spin in opposite direction).
Is this observation correct?
From what I have seen in the Thruster User Guide (https://bluerobotics.com/learn/thruster-usage-guide/#introduction, see section Propeller Direction) the direction of the propeller spin does not change the definition of the forward thrust, because of the usage of mirrored thruster blades.
In that case the TAM would not map the individual thruster forces to the generalized wrench, but rather the force multiplied by the spinning direction?
I am sorry for the extensive questioning of this specific detail, but I have now seen a few different implementations of TAMs for the BlueROV2 heavy that all seem to disagree somehow and I wanted to make sure I can understand your implementation of it, because I do not want to compromise the ll-controller by changing the TAM inappropriately based on wrong assumptions.
(
For reference, I also looked at these alternative TAM implementations:
https://flex.flinders.edu.au/file/27aa0064-9de2-441c-8a17-655405d5fc2e/1/ThesisWu2018.pdf | Page 49
https://doi.org/10.3390/jmse10121898 | Page 23 Figure A4
)
Thank you very much in advance for your response as well as for your work on these repositories, it has been extremely helpful for my project.
Best,
Luis
Beta Was this translation helpful? Give feedback.
All reactions