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

Templates to create a new thruster actuated vehicle model

Musa Morena Marcusso Manhães edited this page May 5, 2017 · 10 revisions

For the following tutorial, all the files can also be found in the uuv_tutorial_rov_model. Here are some templates that can be used when creating a new vehicle model actuated only with thrusters. Following the folder standard for model descriptions, this example will use the catkin package name uuv_descriptions_example and the vehicle model rov_example. To create a new package and the folder structure use the following commands

cd ~/catkin_ws/src
catkin_create_package uuv_descriptions_example
cd uuv_descriptions_example
mkdir -p models/rov_example
cd models/rov_example
mkdir launch urdf robots mesh
touch launch/upload_rov_example.launch
touch robots/rov_example_default.xacro
touch urdf/rov_example_base.xacro
touch urdf/rov_example_snippets.xacro
touch urdf/rov_example_thrusters.xacro
touch urdf/rov_example_sensors.xacro

The templates for each file created can be seen below, edit them to make your model. You can use the RexROV model description and the package configuration files in the uuv_descriptions package as a reference as well.

Model description templates

launch/upload_rov_example.launch

<launch>
  <!-- Debug flag -->
  <arg name="debug" default="0"/>

  <!-- Vehicle's initial pose -->
  <arg name="x"     default="0"/>
  <arg name="y"     default="0"/>
  <arg name="z"     default="-20"/>
  <arg name="roll"  default="0"/>
  <arg name="pitch" default="0"/>
  <arg name="yaw"   default="0"/>

  <!-- Mode to open different robot configurations as set the in file
  nomenclature standard for the files in /robots

  /robots/<model_name>_<mode>.xacro
  -->
  <arg name="mode" default="default"/>

  <!-- Vehicle's namespace -->
  <arg name="namespace" default="rov_example"/>

  <arg name="world_frame" default="world"/>


  <group ns="$(arg namespace)">
    <param name="robot_description"
           command="$(find xacro)/xacro.py '$(find uuv_descriptions_example)/models/rov_example/robots/rov_example_$(arg mode).xacro' debug:=$(arg debug) namespace:=$(arg namespace)" />

    <!-- Run a python script to the send a service call to gazebo_ros to spawn a URDF robot -->
    <node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
          args="-urdf -x $(arg x) -y $(arg y) -z $(arg z) -R $(arg roll) -P $(arg pitch) -Y $(arg yaw) -model $(arg namespace) -param /$(arg namespace)/robot_description"/>

    <!-- A joint state publisher plugin already is started with the model, no need to use the default joint state publisher -->

    <!-- Publish robot model for ROS -->
    <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn="true" output="screen">
      <param name="robot_description" value="/$(arg namespace)/robot_description" />
    </node>
  </group>

  <!-- Publish state and tf for in relation to the world frame -->
  <group ns="$(arg namespace)">
    <node name="ground_truth_to_tf" pkg="message_to_tf" type="message_to_tf" output="screen">
      <param name="odometry_topic" value="/$(arg namespace)/pose_gt" />
      <param name="frame_id" value="/$(arg world_frame)" />
      <param name="tf_prefix" value="$(arg namespace)" />
    </node>
  </group>

</launch>

robots/rov_example_default.xacro

<?xml version="1.0"?>
<robot name="rov_example" xmlns:xacro="http://www.ros.org/wiki/xacro" >

  <!-- Input debug flag -->
  <xacro:arg name="debug" default="0"/>

  <!-- Vehicle's namespace -->
  <xacro:arg name="namespace" default="rov_example"/>

  <!-- Include the ROV macro file -->
  <xacro:include filename="$(find uuv_descriptions_example)/models/rov_example/urdf/rov_example_base.xacro"/>

  <!-- Create the rov_example -->
  <xacro:rov_example_base namespace="$(arg namespace)" debug="$(arg debug)"/>

  <!-- Joint state publisher plugin -->
  <gazebo>
    <plugin name="joint_state_publisher" filename="libjoint_state_publisher.so">
      <robotNamespace>$(arg namespace)</robotNamespace>
      <updateRate>50</updateRate>
    </plugin>
  </gazebo>

</robot>

urdf/rov_example_base.xacro

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
  <!-- Loading some constants -->
  <xacro:include filename="$(find uuv_descriptions)/models/common/urdf/common.urdf.xacro"/>
  <!-- Loading file with sensor macros -->
  <xacro:include filename="$(find uuv_sensor_plugins_ros)/urdf/sensor_snippets.xacro"/>
  <!-- Loading vehicle's specific macros -->
  <xacro:include filename="$(find uuv_descriptions_example)/models/rov_example/urdf/rov_example_snippets.xacro"/>

  <!--
    Vehicle's parameters
  -->

  <xacro:property name="mass" value="0"/>
  <xacro:property name="volume" value="0"/>
  <!-- Center of gravity -->
  <xacro:property name="cog" value="0 0 0"/>
  <!-- Center of buoyancy -->
  <xacro:property name="cob" value="0 0 0"/>
  <!-- Fluid density -->
  <xacro:property name="rho" value="1028"/>

  <!-- Describing the dimensions of the vehicle's bounding box -->
  <xacro:property name="length" value="0"/>
  <xacro:property name="width"  value="0"/>
  <xacro:property name="height" value="0"/>

  <!-- Visual mesh file for the vehicle, usually in DAE (Collada) format -->
  <xacro:property name="visual_mesh_file" value="file://$(find uuv_descriptions_example)/models/rov_example/mesh/vehicle.dae"/>

  <!-- Collision geometry mesh, usually in STL format (it is recommended to keep
  this geometry as simple as possible to improve the performance the physics engine
  regarding the computation of collision forces) -->
  <xacro:property name="collision_mesh_file" value="file://$(find uuv_descriptions_example)/models/rov_example/mesh/vehicle.stl"/>

  <!-- Vehicle macro -->
  <xacro:macro name="rov_example_base" params="namespace debug">

    <!-- Rigid body description of the base link -->
    <link name="${namespace}/base_link">
      <inertial>
        <mass value="${mass}" />
        <origin xyz="${cog}" rpy="0 0 0"/>
        <inertia ixx="0" ixy="0" ixz="0"
                 iyy="0" iyz="0"
                 izz="0" />
      </inertial>

      <visual>
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <geometry>
          <mesh filename="${visual_mesh_file}" scale="1 1 1" />
        </geometry>
      </visual>

      <collision>
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <geometry>
          <mesh filename="${collision_mesh_file}" scale="1 1 1" />
        </geometry>
      </collision>
    </link>

  <gazebo reference="${namespace}/base_link">
    <selfCollide>false</selfCollide>
  </gazebo>

  <!-- Dummy link for the frame in SNAME standard, Gazebo does not offer
  the option to change from ENU standard yet-->
  <xacro:dummy_link name="${namespace}/ned_link" />

  <joint name="ned_joint" type="revolute">
    <!-- This is revolute and not static since gazebo would remove ned_link -->
    <origin xyz="0 0 0" rpy="${pi} 0 0"/>
    <parent link="${namespace}/base_link"/>
    <child link="${namespace}/ned_link"/>
    <limit effort="0" lower="0" upper="0" velocity="0"/>
  </joint>

    <!-- Set up hydrodynamic plugin -->
    <gazebo>
      <plugin name="${namespace}_uuv_plugin" filename="libunderwater_object_ros_plugin.so">
        <!-- Fluid density to be used in the computation of buoyancy forces
        for all links specified below -->
        <fluid_density>${rho}</fluid_density>

        <!-- Name of the current velocity topic -->
        <flow_velocity_topic>hydrodynamics/current_velocity</flow_velocity_topic>

        <!-- Debug flag, if set to true, added-mass, damping and restoring
        forces and moments will be published in separate topics -->
        <debug>${debug}</debug>

        <!-- List of hydrodynamic models this robot's links -->
        <link name="${namespace}/base_link">
          <!-- This flag will make the link neutrally buoyant -->
          <neutrally_buoyant>0</neutrally_buoyant>

          <!-- Link's volume -->
          <volume>${volume}</volume>

          <!-- Link's bounding box, it is used to recalculate the immersed
          volume when close to the surface.
          This is a workaround the invalid bounding box given by Gazebo-->
          <box>
            <width>${width}</width>
            <length>${length}</length>
            <height>${height}</height>
          </box>

          <!-- Center of buoyancy -->
          <center_of_buoyancy>${cob}</center_of_buoyancy>

          <!--
          ----------------------------------------------------
          ----------------------------------------------------
          Choose one of the hydrodynamic models below, all are based on
          Fossen's equation of motion for underwater vehicles

          Reference:
          Fossen, Thor I. Handbook of marine craft hydrodynamics and motion
          control. John Wiley & Sons, 2011.
          ----------------------------------------------------
          ---------------------------------------------------->

          <!-- Fossen's equation of motion -->
          <hydrodynamic_model>
            <type>fossen</type>
            <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 0
            </added_mass>
            <!--
            The linear damping coefficients can be provided as a diagonal (6 elements)
            or a full matrix (36 coefficients), like the added-mass coefficients above
            -->
            <linear_damping>
              0 0 0 0 0 0
            </linear_damping>
            <!--
            The linear damping coefficients proportional to the forward speed
            can be provided as a diagonal (6 elements) or a full matrix (36 coefficients),
            like the added-mass coefficients above.
            This matrix is mostly useful for slender bodies (e.g. AUVs with torpedo shape)
            -->
            <linear_damping_forward_speed>
              0 0 0 0 0 0
            </linear_damping_forward_speed>
            <!--
            The quadratic damping coefficients can be provided as a diagonal (6 elements)
            or a full matrix (36 coefficients), like the added-mass coefficients above
            -->
            <quadratic_damping>
              0 0 0 0 0 0
            </quadratic_damping>
          </hydrodynamic_model>

        </link>
      </plugin>
    </gazebo>

    <!-- Include the thruster modules -->
    <xacro:include filename="$(find uuv_descriptions_example)/models/rov_example/urdf/rov_example_thrusters.xacro"/>

    <!-- Include the sensor modules -->
    <xacro:include filename="$(find uuv_descriptions_example)/models/rov_example/urdf/rov_example_sensors.xacro"/>

  </xacro:macro>

</robot>

urdf/rov_example_sensors.xacro

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

  <!-- Some examples of sensors that can be added to the vehicle frame
  Set the origin of the sensor frames correctly for your application
  Look into the sensor macros in the package uuv_sensor_plugins_ros/urdf for
  more examples.
  -->

  <!-- Mount a 3D pose sensor -->
  <gazebo>
    <plugin name="pose_3d_plugin" filename="libgazebo_ros_p3d.so">
      <robotNamespace>${namespace}</robotNamespace>
      <bodyName>${namespace}/base_link</bodyName>
      <topicName>pose_gt</topicName>
      <frameName>world</frameName>
      <gaussianNoise>0.0</gaussianNoise>
      <updateRate>30</updateRate>
    </plugin>
  </gazebo>

  <!-- Forward-looking sonar sensor -->
  <xacro:forward_multibeam_p900 namespace="${namespace}" parent_link="${namespace}/base_link">
    <origin xyz="0 0 0" rpy="0 0 0"/>
  </xacro:forward_multibeam_p900>

  <!-- DVL  -->
  <xacro:default_dvl namespace="${namespace}" parent_link="${namespace}/base_link">
    <origin xyz="0 0 0" rpy="0 0 0"/>
  </xacro:default_dvl>

  <!-- RPT  -->
  <xacro:default_rpt namespace="${namespace}" parent_link="${namespace}/base_link">
    <origin xyz="0 0 0" rpy="0 0 0"/>
  </xacro:default_rpt>

  <!-- Pressure  -->
  <xacro:default_pressure namespace="${namespace}" parent_link="${namespace}/base_link">
    <origin xyz="0 0 0" rpy="0 0 0"/>
  </xacro:default_pressure>

  <!-- IMU  -->
  <xacro:default_imu namespace="${namespace}" parent_link="${namespace}/base_link">
    <origin xyz="0 0 0" rpy="0 0 0"/>
  </xacro:default_imu>

  <!-- Mount a camera -->
  <xacro:default_camera namespace="${namespace}" parent_link="${namespace}/base_link">
    <origin xyz="0 0 0" rpy="0 0 0"/>
  </xacro:default_camera>

</robot>

urdf/rov_example_snippets.xacro

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

  <!-- Provide the propeller mesh in a separate file with the rotation axis
  over propeller's frame X-axis in DAE (Collada) or STL format.
  -->
  <xacro:property name="prop_mesh_file" value="file://$(find uuv_descriptions_example)/models/rov_example/mesh/propeller.dae"/>

  <!-- Thruster macro with integration of joint and link-->
  <xacro:macro name="thruster_macro" params="robot_namespace thruster_id *origin">

    <!--
    Dummy link as place holder for the thruster frame,
    since thrusters can often be inside the collision geometry
    of the vehicle and may cause internal collisions if set otherwise
    -->
    <link name="${robot_namespace}/thruster_${thruster_id}">

      <visual>
        <geometry>
          <mesh filename="${prop_mesh_file}" scale="1 1 1" />
        </geometry>
      </visual>

      <inertial>
        <mass value="0.001" />
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <inertia ixx="0.000000017" ixy="0.0" ixz="0.0"
               iyy="0.000000017" iyz="0.0"
               izz="0.000000017" />
      </inertial>
    </link>

    <!-- Joint between thruster link and vehicle base link -->
    <joint name="${robot_namespace}/thruster_${thruster_id}_joint" type="continuous">
      <xacro:insert_block name="origin" />
      <axis xyz="1 0 0" />
      <parent link="${robot_namespace}/base_link" />
      <child link="${robot_namespace}/thruster_${thruster_id}" />
    </joint>

    <gazebo>
      <!-- Thruster ROS plugin -->
      <plugin name="${robot_namespace}_${thruster_id}_thruster_model" filename="libthruster_ros_plugin.so">
        <!-- Name of the thruster link -->
        <linkName>${robot_namespace}/thruster_${thruster_id}</linkName>

        <!-- Name of the joint between thruster and vehicle base link -->
        <jointName>${robot_namespace}/thruster_${thruster_id}_joint</jointName>

        <!-- Thruster force output topic name -->
        <thrustTopic>${robot_namespace}/thrusters/${thruster_id}/thrust</thrustTopic>

        <!-- Thruster commmand input topic name -->
        <inputTopic>${robot_namespace}/thrusters/${thruster_id}/input</inputTopic>

        <!-- Gain of the input command signal -->
        <gain>1</gain>

        <!-- Maximum allowed input value for the input signal for thruster unit -->
        <clampMax>0</clampMax>

        <!-- Minimum allowed value for the input signal for thruster unit -->
        <clampMin>0</clampMin>

        <!--
        Value from 0 to 1 to set the efficiency of the output thrust force
        Default value is 1.0
        -->
        <thrust_efficiency>1</thrust_efficiency>

        <!--
        Value from 0 to 1 to set the efficiency of the propeller as a factor
        to be multiplied to the current value of the state variable at each
        iteration.
        Default value is 1.0
        -->
        <propeller_efficiency>1</propeller_efficiency>

        <!--
        ----------------------------------------------------
        ----------------------------------------------------
        Choose one of the propeller dynamics models below for your implementation
        This will describe the dynamic model for the state variable of your thruster unit,
        which can be, e.g., the angular velocity of the propeller.
        ----------------------------------------------------
        ---------------------------------------------------->

        <!-- Simple zero-order model -->
        <dynamics>
          <type>ZeroOrder</type>
        </dynamics>

        <!-- First order model, gain used is specified above -->
        <dynamics>
          <type>FirstOrder</type>
          <timeConstant>0.0</timeConstant>
        </dynamics>

        <!-- Yoerger's nonlinear dynamic model
        For information on the model description:
        D. R. Yoerger, J. G. Cooke, and J.-J. E. Slotine, “The influence of
        thruster dynamics on underwater vehicle behavior and their incorporation
        into control system design,” IEEE Journal of Oceanic Engineering, vol. 15, no. 3, pp. 167–178, Jul. 1990.
        -->
        <dynamics>
          <type>Yoerger</type>
          <alpha>0.0</alpha>
          <beta>0.0</beta>
        </dynamics>

        <!-- Bessa's nonlinear dynamic model
        For information on the model description:
        Bessa, Wallace Moreira, Max Suell Dutra, and Edwin Kreuzer. "Thruster
        dynamics compensation for the positioning of underwater robotic vehicles
        through a fuzzy sliding mode based approach." ABCM Symposium Series in
        Mechatronics. Vol. 2. 2006.
        -->
        <dynamics>
          <type>Bessa</type>
          <Jmsp>0.0</Jmsp>
          <Kv1>0.0</Kv1>
          <Kv2>0.0</Kv2>
          <Kt>0.0</Kt>
          <Rm>0.0</Rm>
        </dynamics>

        <!--
        ----------------------------------------------------
        ----------------------------------------------------
        Choose one of the model for the steady-state curve describing the
        relationship between the state variable and the output thrust force
        ----------------------------------------------------
        ---------------------------------------------------->

        <!-- Basic curve
        Input: x
        Output: thrust
        Function: thrust = rotorConstant * x * abs(x)
        -->
        <conversion>
          <type>Basic</type>
          <rotorConstant>0.0</rotorConstant>
        </conversion>

        <!-- Dead-zone nonlinearity described in Bessa, 2006
        Input: x
        Output: thrust
        Function:
        thrust = rotorConstantL * (x * abs(x) - deltaL), if x * abs(x) <= deltaL
        thrust = 0, if deltaL < x * abs(x) < deltaR
        thrust = rotorConstantR * (x * abs(x) - deltaR), if x * abs(x) >= deltaL
        -->
        <conversion>
          <type>Bessa</type>
          <rotorConstantL>0.0</rotorConstantL>
          <rotorConstantR>0.0</rotorConstantR>
          <deltaL>0.0</deltaL>
          <deltaR>0.0</deltaR>
        </conversion>

        <!-- Linear interpolation
        If you have access to the thruster's data sheet, for example,
        you can enter samples of the curve's input and output values
        and the thruster output will be found through linear interpolation
        of the given samples.
        -->
        <conversion>
          <type>LinearInterp</type>
          <inputValues>0 1 2 3</inputValues>
          <outputValues>0 1 2 3</outputValues>
        </conversion>

      </plugin>
    </gazebo>

    <gazebo reference="${robot_namespace}/thruster_${thruster_id}">
      <selfCollide>false</selfCollide>
    </gazebo>
  </xacro:macro>

</robot>

urdf/rov_example_thrusters.xacro

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
  <!-- Adding the thruster units with the macro created in rov_example_snippets.xacro -->

  <xacro:thruster_macro
    robot_namespace="${namespace}"
    thruster_id="0">
    <origin xyz="0 0 0" rpy="0 0 ${pi}" />
  </xacro:thruster_macro>

  <xacro:thruster_macro
    robot_namespace="${namespace}"
    thruster_id="1">
    <origin xyz="0 0 0" rpy="0 0 ${pi}" />
  </xacro:thruster_macro>

  <xacro:thruster_macro
    robot_namespace="${namespace}"
    thruster_id="2">
    <origin xyz="0 0 0" rpy="0 -${0.5*pi} 0" />
  </xacro:thruster_macro>

</robot>

Starting your new model in Gazebo

Build your workspace again before testing your new model with catkin_make install. To launch the new model for this example, use (don't forget to change the package and model names)

roslaunch uuv_descriptions ocean_waves.launch

and then

roslaunch uuv_descriptions_example upload_rov_example.launch