-
Notifications
You must be signed in to change notification settings - Fork 49
Home
This page details how to create a new underwater vehicle-manipulator (with or without joints) and how is the control done. We begin by some considerations about using UWSim or not for the rendering.
An example is given in the demo package.
In this package, UWSim is optionnal and may be used for the visual rendering instead of the Gazebo gui.
When not using UWSim, the objects (robots, terrain , other objects) have to be spawned in a classical fashion in Gazebo, typically with a launch file calling the gazebo_ros/spawn_model node.
To use both UWSim for the rendering and Gazebo for the dynamics, the main file is usually the scene xlm file that is used by UWSim. In this case the Gazebo spawner can be automatically generated if needed, as UWSim and Gazebo do not use the same file path convention. The UWSim launch file should then be written first, then a script can be called with:
rosrun freefloating_gazebo uwsim_scene_to_gazebo_spawner.py <uwsim launchfile>
It will then generate a gazebo_spawner.launch that will spawn the objects at the same poses in Gazebo. These files can also of course be written by hand.
Gazebo will publish the ground truth odometry of all moving objects in their state topic, and the UWSim scene xml should subscribe to the same topics in order to have the positions updated.
Basic hydrodynamics are handled through a world plugin that should be loaded in Gazebo.
The world file is freefloating_gazebo/world/underwater.world and will then simulate buoyancy and hydrodynamic damping forces for the links that are defined with such properties.
The model can be written in SDF or URDF, though to my knowledge UWSim cannot handle SDF models. The main additions compared to a classical robot model lay in two fields
Each link of the model can be added a buoyancy tag. It behaves more or less like the inertial> tag. The syntax was updated but the initial syntax is still parsed. The damping and added mass should be computed at the center of buoyancy, expressed in the link axis. Default damping is linear if left unspecified.
<fluid>
<density>1</density>
<origin xyz= "0 0 0.04"/>
<buoyancy>
<compensation>1.01</compensation>
<limit radius="0.01"/>
</buoyancy>
<hydrodynamics>
<damping xyz="50 100 60" rpy="50 50 50" type="linear"/>
<damping xyz="5 10 6" rpy="5 5 5" type="quadratic"/>
<added_mass>0 0 0 0 0
0 0 0 0 0 0
0 0 0 0 0 0
0 0 0 0 0 0
0 0 0 0 0 0
0 0 0 0 0 0</added_mass>
</hydrodynamics>
</fluid>
<buoyancy>
<compensation>1.01</compensation>
<origin xyz= "0 0 0.04"/>
<limit radius=".5"/>
<damping xyz="60 100 100" rpy="20 50 50"/>
</buoyancy>
Elements are as follows:
- compensation: how is the buoyancy force compensating for the gravity. 1 means the object is weightless, above 1 means it will naturally float (which is hopefully the case for your AUV)
- origin: the XYZ coordinates of the center of buoyancy. This point is typically above the center of gravity in order to induce a keel effect
- limit: the buoyancy force will begin to decrease if the robot approaches the water surface. The limit value set this minimum distance. A good approximation is to give the distance between the center and the top of the robot.
- damping: the coefficients that are used to simulate hydrodynamic damping. 6 values are needed, for the 6 drag coefficients on the translation and rotation axis in the robot frame. Damping can be linear (default if unspecified) or quadratic
- added mass: coefficients of the added mass matrix, expressed at the center of buoyancy in the link axis system
The freefloating_gazebo_control_plugin should be used in the robot model in order to simulate thrusters. In the current state of the simulation, only fixed thrusters can be simulated but steerable thrusters are being developped.
The plugin is called in a classical way:
<gazebo>
<!-- Gazebo plugin listens to the body-->
<plugin name="freefloating_gazebo_control" filename="libfreefloating_gazebo_control.so">
<switchService>switch</switchService>
<updateRate>100</updateRate>
<link>base_link</link>
<!-- for each thruster, give the map to XYZ+RPY and the maximum effort -->
<thruster>
<map>-1 0 0 0 0 ${-body_width/2}</map>
<effort>30</effort>
</thruster>
</plugin>
</gazebo>
The elements are used as follow:
- switchService: service to call to switch OFF or ON the control part
- link: the robot link to which the thrusters are attached
- thruster/map: for each thruster, the thruster control matrix is defined to map the thruster effort to the body wrench
- thruster/effort: the maximum effort for this thruster
Instead of the map, a name field including some link name may be given. In this case the parser will assume this is a thruster link, where the Z-axis is the thrust orientation.
Once such a model is spawned in Gazebo, the following topics are published and subscribed to (in each robot namespace):
- Published
- state (nav_msgs/Odometry): ground truth odometry of any moving object.
- joint_states (sensor_msgs/JointState): joint states if any
- thruster_use (std_msgs/Float32MultiArray): percentage of effort on each thruster
- Subscribed
- thruster_command (sensor_msgs/JointState): Thrust setpoint (in Newton) for all thrusters. The effort field of the JointState message should be used.
- joint_command (sensor_msgs/JointState): effort setpoint for each joint (if any)
As we can see, the simulation by itself only provided low-level control (wrench for the robot body, effort for the joints). The package also includes a basic PID control node for the body axis and the joints of the robot. It need a configuration file (as seen in the examples) containing the list of axis gains.
-
Published
- thruster_command (sensor_msgs/JointState): Thrust setpoint
- joint_command (sensor_msgs/JointState): effort setpoint for each joint (if any)
-
Subscribed
- state (nav_msgs/Odometry): ground truth odometry of any moving object.
- joint_states (sensor_msgs/JointState): joint states if any
- body_position_setpoint (geometry_msgs/PoseStamped)
- body_velocity_setpoint (geometry_msgs/TwistStamped)
- body_wrench_setpoint (geometry_msgs/WrenchStamped)
-
Services to switch the control mode of some axes
-
controllers/{joint,body}_{position,velocity,wrench}_control
-
the request is the list of axis to be switched to this mode:
rosservice call controllers/body_position_control "axes: ['roll', 'pitch', 'z']"
-
-
The overall control mode can be passed as
body_control
orjoint_control
to the PID node. Possible values are:- for the body: position, velocity, effort
- depth (where roll and pitch are position-controlled to 0, z is position-controlled and x, y and yaw are velocity-controlled)
- for the joints: position, velocity, effort
- for the body: position, velocity, effort