Skip to content
This repository has been archived by the owner on Feb 6, 2023. It is now read-only.

Explaining the configuration of the ROV model description

Musa Morena Marcusso Manhães edited this page Nov 17, 2016 · 4 revisions

Explaining the configuration of the ROV model description

Building a new ROV or a vehicle actuated only with thrusters is going to be shown here. For this, we will use as an example our own RexROV model. This tutorial shows how to build the model catkin package and how to setup the URDF files in order to load the model in Gazebo and use ROS as a middleware.

The package description

Assuming that you have a catkin workspace configured (if not, please follow this tutorial). We will analyze the folder structure in the uuv_descriptions package, but if you need to build your own package, do it as follows:

cd ~/catkin_ws/src
catkin_create_pkg uuv_descriptions_rov_example
cd uuv_descriptions_rov_example
mkdir -p models/rov_example/launch
mkdir -p models/rov_example/mesh
mkdir -p models/rov_example/robots
mkdir -p models/rov_example/urdf

This folder structure is only a suggestion for your model and in this standard, the vehicle models are all included inside the models folder locate in the catkin package. Each model has then its own folder where the following folders are created:

  • launch: The ROS launch files to spawn the model in the Gazebo environment
  • mesh: Visual and collision meshes for the vehicle and its propellers
  • urdf: Contains XACRO files with macros describing the vehicle model
  • robots: Contains XACRO files setting up different instances of the vehicle with different configurations

The idea with this structure is to set a basic vehicle model and then implement different actuator and sensor configurations of the same vehicle in the robots folder. For instance, the current configuration of the RexROV in the uuv_descriptions package allows the vehicle to be spawned with or without a manipulator arm. This makes it easy to store your different configurations that can vary according to the mission you are simulating.

Along with the folder structure, a filename nomenclature is also suggested here. If you browse the uuv_descriptions folder, the main files are named according to the standard below:

  • launch/upload_<model_name>.launch
  • robots/<model_name>_<mode>.xacro
  • urdf/<model_name>_base.xacro

In this case, the model_name is rexrov, mode is set, for example, as default for the basic configuration of the vehicle and as sonar for a vehicle with a forward looking sonar mounted on its frame.

Setting up the hydrodynamic model

Inside the file urdf/rexrov_base.xacro, one of the most important parts of the description is the configuration of the hydrodynamic model.

<gazebo>
  <plugin name="uuv_plugin" filename="libunderwater_object_ros_plugin.so">
    <fluid_density>1028.0</fluid_density>
    <flow_velocity_topic>hydrodynamics/current_velocity</flow_velocity_topic>
    <debug>${debug}</debug>
    <link name="${namespace}/base_link">
      <volume>${volume}</volume>
      <box>
        <width>1.5</width>
        <length>2.6</length>
        <height>1.6</height>
      </box>
      <center_of_buoyancy>${cob}</center_of_buoyancy>
      <!-- Added mass: see p.28 in Berg2012 -->
      <hydrodynamic_model>
        <type>fossen</type>
        <added_mass>
           779.79 -6.8773 -103.32 8.5426 -165.54 -7.8033
          -6.8773 1222 51.29 409.44 -5.8488 62.726
            -103.32 51.29 3659.9 6.1112 -386.42 10.774
            8.5426 409.44 6.1112 534.9 -10.027 21.019
            -165.54 -5.8488 -386.42 -10.027 842.69 -1.1162
            -7.8033 62.726 10.775 21.019 -1.1162 224.32
        </added_mass>
        <!-- Linear damping: see p.31 in Berg2012 -->
        <linear_damping>-74.82 -69.48 -728.4 -268.8 -309.77 -105</linear_damping>
        <!-- Non-linear damping: see p.30 in Berg2012 -->
        <quadratic_damping>-748.22 -992.53 -1821.01 -672 -774.44 -523.27</quadratic_damping>
      </hydrodynamic_model>
    </link>
  </plugin>
</gazebo>

The parameters fluid_density, flow_velocity_topic and debug are valid for all the links contained in this model. The debug flag will set the plugin to publish the added-mass, damping and restoring forces in separate topics.

For the hydrodynamic and hydrostatic forces and moments to be generated, each link that will be subject to these forces and its parameter need to be explicitly listed in the plugin block. There are several sources in the literature for understanding the modeling of underwater vehicles, one of them being these lecture notes.

For each link listed, a buoyancy force is generated using the parameters volume, box and center_of_buoyancy. box refers to the bounding box of the vehicle and it is a quick fix since the exact volume of the link cannot be accurately retrieved inside the Gazebo simulation environment. It will be used to recalculate the buoyancy force once the vehicle reaches the sea surface.

The hydrodynamic model implemented is Fossen's equation of motion for underwater vehicles. The parameters needed for this are the added_mass, linear_damping and quadratic_damping. The type parameter is given because the plugin offers some implementations to calculate hydrodynamic models for simple geometries, such as spheres. This is useful during the construction of the model to test if the model can be loaded in the environment correctly or if the user is unsure about the exact hydrodynamic parameters. To use the Fossen's equation directly, type should be set with the string fossen, as shown above. To set the model for a sphere, for example, in the fluid set the hydrodynamic_model block as follows:

<hydrodynamic_model>
  <type>sphere</type>
  <radius>some radius</radius>
</hydrodynamic_model>

Further models for simple geometries such as cylinders and spheroids are currently under implementation.

Thrusters

The thrusters all have their individual frames (see image below) and each runs its own instance of the thruster plugin. Therefore, the vehicle mesh should not contain the propellers. The propeller mesh must be stored separately in the mesh folder.

RexROV and thruster forces

To make the specification of the vehicle description easier, a thruster macro can be created, shown below in the snippet from this file. It creates a "place holder" link that will be installed on the vehicle frame on a given pose. This link has no meaninful physical meaning mainly due to the fact that many vehicles have their thrusters installed inside their collision geometries and this could lead to internal collisions in the simulation environment.

Having this link will provide information about the relative pose of the thruster to the vehicle frame, which is used by the thruster manager module to generate the thruster allocation matrix in runtime.

<!-- Thruster joint and link snippet -->
<xacro:macro name="thruster_macro" params="namespace thruster_id *origin">
  <joint name="${namespace}/thruster_${thruster_id}_joint" type="continuous">
    <xacro:insert_block name="origin"/>
    <axis xyz="1 0 0"/>
    <parent link="${namespace}/base_link"/>
    <child link="${namespace}/thruster_${thruster_id}"/>
  </joint>
  <link name="${namespace}/thruster_${thruster_id}">
    <xacro:box_inertial x="0" y="0" z="0" mass="0.001">
      <origin xyz="0 0 0" rpy="0 0 0"/>
    </xacro:box_inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <mesh filename="${prop_mesh_file}" scale="1 1 1"/>
      </geometry>
    </visual>
    <collision>
      <geometry>
        <cylinder length="0.000001" radius="0.000001"/>
      </geometry>
      <origin xyz="0 0 0" rpy="0 ${0.5*pi} 0"/>
    </collision>
  </link>
  <gazebo>
    <plugin name="${namespace}_${thruster_id}_thruster_model" filename="libthruster_ros_plugin.so">
      <linkName>${namespace}/thruster_${thruster_id}</linkName>
      <jointName>${namespace}/thruster_${thruster_id}_joint</jointName>
      <thrustTopic>${namespace}/thrusters/${thruster_id}/thrust</thrustTopic>
      <inputTopic>${namespace}/thrusters/${thruster_id}/input</inputTopic>
      <dynamics>
        <type>FirstOrder</type>
        <timeConstant>0.05</timeConstant>
      </dynamics>
      <conversion>
        <type>Basic</type>
        <rotorConstant>0.00031</rotorConstant>
      </conversion>
    </plugin>
  </gazebo>
</xacro:macro>

Using this thruster macro, each thruster unit can be configured in the robot model description as in the example below

<xacro:thruster_macro namespace="${namespace}" thruster_id="0">
  <origin xyz="-0.890895 0.334385 0.528822" rpy="${0*d2r} ${-74.53*d2r} ${-53.21*d2r}"/>
</xacro:thruster_macro>

References

Fossen, Thor. Lecture Notes TTK 4190 Guidance and Control of Vehicles, NTNU