uuvsimulator / uuv_simulator

Gazebo/ROS packages for underwater robotics simulation
https://uuvsimulator.github.io/
Other
693 stars 361 forks source link

Newly added spherical robot keeps jumping in and out of water #254

Closed touhid1259 closed 6 years ago

touhid1259 commented 6 years ago

Hi

I am new to gazebo, ROS and UUV simulator. I am trying to use UUV Simulator. I am trying to add new robot according to your documentation. I have added one sphere robot with radius .2. But, the robot is jumping up and down of water (Images attached). Actually, my expectation was:- robot may sink or float or may stays stable inside water based on its mass. So, can you please help me on this regard. Why the robot is keeps jumping up and down inside water?

sphere robot parameters are: mass: 30 (I have tweaked it around with high and low values. Sometime it sinks which is okay but the above issue is my problem) radius: .2 volume: 0.0335 (using the equation: 4/3 pi radius radius radius) center of gravity co-ordinate: 0 0 0 center of buoyancy co-ordinate: 0 0 0.01 and fluid density is: 1028

gazebo2 gazebo3 geazebo1

musamarcusso commented 6 years ago

Hi @touhid1259, from a first glance in this problem, it seems to me that the damping coefficients may not be enough to slow down the ball. Could you copy the complete model you are using here? Then it might be easier to evaluate what to do :)

touhid1259 commented 6 years ago

Hi musamarcusso

Thanks for the reply. Below are the generated robot files that are being generated following the documentation. I have changed the files to my need. In my case, I think only default.xacro, gazebo.xacro, base.xacro and sensors.xacro are used. But I added all the files. One thing to note, from gazebo.xacro, I have used the hydrodynamic model for sphere instead of fossen. So, may be that is the issue here, as I can see that the damping coefficients generating here. Another thing is, when I ran the upload.launch for the robot I get the below message regarding added_mass and damping coefficients:

ea_robot::ea_robot/base_link::added_mass
     17.2243           0           0           0           0           0
           0     17.2243           0           0           0           0
           0           0     17.2243           0           0           0
           0           0           0           0           0           0
           0           0           0           0           0           0
           0           0           0           0           0           0
ea_robot::ea_robot/base_link::scaling_added_mass
ea_robot::ea_robot/base_link::scaling_added_mass
ea_robot::ea_robot/base_link::offset_added_mass
ea_robot::ea_robot/base_link::offset_added_mass
ea_robot::ea_robot/base_link::linear_damping
ea_robot::ea_robot/base_link::linear_damping
           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
ea_robot::ea_robot/base_link::linear_damping_forward_speed
ea_robot::ea_robot/base_link::linear_damping_forward_speed
           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
ea_robot::ea_robot/base_link::quadratic_damping
ea_robot::ea_robot/base_link::quadratic_damping
           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

default.xacro

<?xml version="1.0"?>
<robot name="ea_robot" xmlns:xacro="http://www.ros.org/wiki/xacro" >
  <xacro:arg name="debug" default="0"/>
  <xacro:arg name="namespace" default="ea_robot"/>

  <!-- ea_robot's genome related arguments -->          
  <xacro:arg name="box1GenomeBit" default= '0' />
  <xacro:arg name="box2GenomeBit" default= '0' />
  <xacro:arg name="box3GenomeBit" default= '0' />
  <xacro:arg name="box4GenomeBit" default= '0' />
  <xacro:arg name="box5GenomeBit" default= '0' />
  <xacro:arg name="box6GenomeBit" default= '0' />
  <xacro:arg name="box7GenomeBit" default= '0' />
  <xacro:arg name="box8GenomeBit" default= '0' />

  <!-- Include the ROV macro file -->
  <xacro:include filename="$(find ea_robot_description)/urdf/base.xacro"/>
  <xacro:include filename="$(find ea_robot_description)/urdf/gazebo.xacro"/>

  <!-- Create the ea_robot -->
  <xacro:ea_robot_base namespace="$(arg namespace)" box1GenomeBit="$(arg box1GenomeBit)" box2GenomeBit="$(arg box2GenomeBit)"
                    box3GenomeBit="$(arg box3GenomeBit)" box4GenomeBit="$(arg box4GenomeBit)"
                    box5GenomeBit="$(arg box5GenomeBit)" box6GenomeBit="$(arg box6GenomeBit)"
                    box7GenomeBit="$(arg box7GenomeBit)" box8GenomeBit="$(arg box8GenomeBit)" >
    <!-- The underwater object plugin is given as an input block parameter to
     allow the addition of external models of manipulator units -->
    <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>$(arg debug)</debug>
        <!-- Adding the hydrodynamic and hydrostatic parameters for the vehicle-->
        <xacro:ea_robot_hydro_model namespace="$(arg namespace)"/>
        <!--
          In case other modules are added to the vehicle (such as a manipulator)
          that also have link running with the underwater object plugin, they
          should also be added in this block. For this, this new module should
          have a file similar to gazebo.xacro above with the description of the
          parameter necessary for the underwater object plugin to be initialized.
        -->
      </plugin>
    </gazebo>
  </xacro:ea_robot_base>

  <!-- Joint state publisher plugin -->
  <xacro:default_joint_state_publisher namespace="$(arg namespace)" update_rate="10"/>

</robot>

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_ros_plugins)/urdf/sensor_snippets.xacro"/>
  <!-- Loading the UUV simulator ROS plugin macros -->
  <xacro:include filename="$(find uuv_gazebo_ros_plugins)/urdf/snippets.xacro"/>  
  <!-- Loading vehicle's specific macros -->
  <xacro:include filename="$(find ea_robot_description)/urdf/snippets.xacro"/>

  <!--
    Vehicle's parameters (remember to enter the model parameters below)
  -->
  <!-- mass of sphere link of ea_robot -->
  <xacro:property name="mass" value="30"/>
  <!-- <xacro:property name="mass" value="1862.87"/> --> <!-- mass data from rexrov model -->
  <!-- radius of sphere link of ea_robot -->
  <xacro:property name="radius" value=".2"/>
  <!-- mass of box link of ea_robot -->
  <xacro:property name="box_mass" value="8"/>
  <!-- length, width and hight of box link of ea_robot -->
  <xacro:property name="lwh" value=".1154"/>
  <!-- Center of gravity -->
  <xacro:property name="cog" value="0 0 0"/>
  <!-- Fluid density -->
  <xacro:property name="rho" value="1028"/>

  <!-- Vehicle macro -->
  <xacro:macro name="ea_robot_base" params="namespace box1GenomeBit box2GenomeBit box3GenomeBit box4GenomeBit box5GenomeBit box6GenomeBit box7GenomeBit box8GenomeBit *gazebo">

      <!-- Rigid body description of the base link -->

        <material name="ea_blue">
            <color rgba="0 0 0.8 1"/>
        </material>

        <material name="ea_white">
            <color rgba="1 1 1 1"/>
        </material>

        <link name="${namespace}/base_link">
            <visual>
                <origin xyz="0 0 0" rpy="0 0 0"/>
                <geometry>
                    <sphere radius="${radius}"/>
                </geometry>
                <material name="ea_white"/>
            </visual>

            <collision>
                <origin xyz="0 0 0" rpy="0 0 0"/>
                <geometry>
                    <sphere radius="${radius}"/>
                </geometry>
            </collision>

            <inertial>
                <mass value="${mass}" />
                <origin xyz="${cog}" rpy="0 0 0"/>
                <inertia ixx="${2/3 * mass * radius * radius}" ixy="0" ixz="0" iyy="${2/3 * mass * radius * radius}" iyz="0" izz="${2/3 * mass * radius * radius}"/>
                <!-- <inertia ixx="5.33" ixy="0" ixz="0" iyy="5.33" iyz="0" izz="5.33"/> this one for mass: 200 -->
            </inertial>

        </link>

        <link name="dummy_link">
        </link>

        <joint name="base_to_dummy_link" type="fixed">
            <parent link="${namespace}/base_link"/>
            <child link="dummy_link"/>
        </joint>

        <link name="box_1">
            <visual>
                <geometry>
                    <box size="${lwh} ${lwh} ${lwh}"/>
                </geometry>
                <material name="ea_blue"/>
            </visual>
            <xacro:if value="${box1GenomeBit == 1}">
                <inertial>
                    <mass value="${box_mass}"/>
                    <inertia ixx="${1/6 * box_mass * lwh * lwh}" ixy="0" ixz="0" iyy="${1/6 * box_mass * lwh * lwh}" iyz="0" izz="${1/6 * box_mass * lwh * lwh}"/>
                </inertial>
            </xacro:if>
        </link>

        <joint name="base_to_box_1" type="fixed">
            <parent link="${namespace}/base_link"/>
            <child link="box_1"/>
            <origin xyz="-.057 -.057 .057"/>
        </joint>

        <link name="box_2">
            <visual>
                <geometry>
                    <box size="${lwh} ${lwh} ${lwh}"/>
                </geometry>
                <material name="ea_blue"/>
            </visual>
            <xacro:if value="${box2GenomeBit == 1}">
                <inertial>
                    <mass value="${box_mass}"/>
                    <inertia ixx="${1/6 * box_mass * lwh * lwh}" ixy="0" ixz="0" iyy="${1/6 * box_mass * lwh * lwh}" iyz="0" izz="${1/6 * box_mass * lwh * lwh}"/>
                </inertial>
            </xacro:if>
        </link>

        <joint name="base_to_box_2" type="fixed">
            <parent link="${namespace}/base_link"/>
            <child link="box_2"/>
            <origin xyz="-.057 .057 .057"/>
        </joint>

        <link name="box_3">
            <visual>
                <geometry>
                    <box size="${lwh} ${lwh} ${lwh}"/>
                </geometry>
                <material name="ea_blue"/>
            </visual>
            <xacro:if value="${box3GenomeBit == 1}">
                <inertial>
                    <mass value="${box_mass}"/>
                    <inertia ixx="${1/6 * box_mass * lwh * lwh}" ixy="0" ixz="0" iyy="${1/6 * box_mass * lwh * lwh}" iyz="0" izz="${1/6 * box_mass * lwh * lwh}"/>
                </inertial>
            </xacro:if>
        </link>

        <joint name="base_to_box_3" type="fixed">
            <parent link="${namespace}/base_link"/>
            <child link="box_3"/>
            <origin xyz=".057 -.057 .057"/>
        </joint>

        <link name="box_4">
            <visual>
                <geometry>
                    <box size="${lwh} ${lwh} ${lwh}"/>
                </geometry>
                <material name="ea_blue"/>
            </visual>
            <xacro:if value="${box4GenomeBit == 1}">
                <inertial>
                    <mass value="${box_mass}"/>
                    <inertia ixx="${1/6 * box_mass * lwh * lwh}" ixy="0" ixz="0" iyy="${1/6 * box_mass * lwh * lwh}" iyz="0" izz="${1/6 * box_mass * lwh * lwh}"/>
                </inertial>
            </xacro:if>
        </link>

        <joint name="base_to_box_4" type="fixed">
            <parent link="${namespace}/base_link"/>
            <child link="box_4"/>
            <origin xyz=".057 .057 .057"/>
        </joint>

        <link name="box_5">
            <visual>
                <geometry>
                    <box size="${lwh} ${lwh} ${lwh}"/>
                </geometry>
                <material name="ea_blue"/>
            </visual>
            <xacro:if value="${box5GenomeBit == 1}">
                <inertial>
                    <mass value="${box_mass}"/>
                    <inertia ixx="${1/6 * box_mass * lwh * lwh}" ixy="0" ixz="0" iyy="${1/6 * box_mass * lwh * lwh}" iyz="0" izz="${1/6 * box_mass * lwh * lwh}"/>
                </inertial>
            </xacro:if>
        </link>

        <joint name="base_to_box_5" type="fixed">
            <parent link="${namespace}/base_link"/>
            <child link="box_5"/>
            <origin xyz="-.057 -.057 -.057"/>
        </joint>

        <link name="box_6">
            <visual>
                <geometry>
                    <box size="${lwh} ${lwh} ${lwh}"/>
                </geometry>
                <material name="ea_blue"/>
            </visual>
            <xacro:if value="${box6GenomeBit == 1}">
                <inertial>
                    <mass value="${box_mass}"/>
                    <inertia ixx="${1/6 * box_mass * lwh * lwh}" ixy="0" ixz="0" iyy="${1/6 * box_mass * lwh * lwh}" iyz="0" izz="${1/6 * box_mass * lwh * lwh}"/>
                </inertial>
            </xacro:if>
        </link>

        <joint name="base_to_box_6" type="fixed">
            <parent link="${namespace}/base_link"/>
            <child link="box_6"/>
            <origin xyz="-.057 .057 -.057"/>
        </joint>

        <link name="box_7">
            <visual>
                <geometry>
                    <box size="${lwh} ${lwh} ${lwh}"/>
                </geometry>
                <material name="ea_blue"/>
            </visual>
            <xacro:if value="${box7GenomeBit == 1}">
                <inertial>
                    <mass value="${box_mass}"/>
                    <inertia ixx="${1/6 * box_mass * lwh * lwh}" ixy="0" ixz="0" iyy="${1/6 * box_mass * lwh * lwh}" iyz="0" izz="${1/6 * box_mass * lwh * lwh}"/>
                </inertial>
            </xacro:if>
        </link>

        <joint name="base_to_box_7" type="fixed">
            <parent link="${namespace}/base_link"/>
            <child link="box_7"/>
            <origin xyz=".057 -.057 -.057"/>
        </joint>

        <link name="box_8">
            <visual>
                <geometry>
                    <box size="${lwh} ${lwh} ${lwh}"/>
                </geometry>
                <material name="ea_blue"/>
            </visual>
            <xacro:if value="${box8GenomeBit == 1}">
                <inertial>
                    <mass value="${box_mass}"/>
                    <inertia ixx="${1/6 * box_mass * lwh * lwh}" ixy="0" ixz="0" iyy="${1/6 * box_mass * lwh * lwh}" iyz="0" izz="${1/6 * box_mass * lwh * lwh}"/>
                </inertial>
            </xacro:if>
        </link>

        <joint name="base_to_box_8" type="fixed">
            <parent link="${namespace}/base_link"/>
            <child link="box_8"/>
            <origin xyz=".057 .057 -.057"/>
        </joint>       

      <!--  </link> -->

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

    <!-- Set up hydrodynamic plugin given as input parameter -->
    <xacro:insert_block name="gazebo"/>

    <!-- Include the sensor modules -->
    <xacro:include filename="$(find ea_robot_description)/urdf/sensors.xacro"/>

  </xacro:macro>

</robot>

gazebo.xacro


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

    <!-- Center of buoyancy -->
    <xacro:property name="ea_robot_cob" value="0.0 0.0 0.01"/>

    <!-- Vehicle's actual volume (Gazebo cannot compute the volume out of the mesh) -->
    <!-- 
        Taking the volume of a solid sphere using the equation: 
            4/3 * pi * radius * radius * radius 
            where, radius = .2
    -->
    <xacro:property name="ea_robot_volume" value="0.0335"/>
    <!-- <xacro:property name="ea_robot_volume" value="1.83826"/> --> <!-- volume data from rexrov model -->

    <!-- Describing the dimensions of the vehicle's bounding box
    Taking the diameter + .1m of the sphere -->
    <xacro:property name="ea_robot_length" value=".5"/>
    <xacro:property name="ea_robot_width"  value=".5"/>
    <xacro:property name="ea_robot_height" value=".5"/>

    <xacro:macro name="ea_robot_hydro_model" params="namespace">
      <!-- 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>${ea_robot_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>${ea_robot_width}</width>
          <length>${ea_robot_length}</length>
          <height>${ea_robot_height}</height>
        </box>

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

        <!-- 2) This computes the added-mass and damping parameters for a sphere
        in the fluid with the given radius -->
        <hydrodynamic_model>
          <type>sphere</type>
          <radius>.2</radius>
        </hydrodynamic_model>

      </link>
    </xacro:macro>

</robot>

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_ros_plugins/urdf for
    more examples or add you own custom sensor units.
  -->

  <!-- Mount a GPS. -->
  <!-- <xacro:default_gps namespace="${namespace}" parent_link="${namespace}/base_link" />  -->

  <!-- Mount a Pose 3D sensor. -->
  <xacro:default_pose_3d namespace="${namespace}" parent_link="${namespace}/base_link" />

  <!-- 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" suffix="">
    <origin xyz="0 0 0" rpy="0 0 0"/>
  </xacro:default_camera>

</robot>

actuators.xacro

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
    <!-- Adding the thruster units with the macro created in snippets.xacro -->
    <!--
    Important:
        - The thruster IDs must be given as integers and must be unique to each thruster unit
        - The thruster pose in the <origin> block is relative to the body's center of mass. Be
          aware that Gazebo does not use the SNAME convention per default.
    -->

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

    <xacro:thruster_macro robot_namespace="${namespace}" thruster_id="1">
        <origin xyz="0 0 -.15" 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> -->

    <!-- Instantiate fins, if necessary -->
    <!-- 
    <xacro:fin_macro namespace="${namespace}" fin_id="0">
      <origin xyz="0 0 0" rpy="0 0 0" />
    </xacro:fin_macro>
    <xacro:fin_macro namespace="${namespace}" fin_id="1">
      <origin xyz="0 0 0" rpy="0 0 0" />
    </xacro:fin_macro>
    <xacro:fin_macro namespace="${namespace}" fin_id="2">
      <origin xyz="0 0 0" rpy="0 0 0" />
    </xacro:fin_macro>
    <xacro:fin_macro namespace="${namespace}" fin_id="3">
      <origin xyz="0 0 0" rpy="0 0 0" />
    </xacro:fin_macro>
    -->
</robot>

snippets.xacro


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

  <!-- 

  MACRO FOR THRUSTER UNITS  

  -->

  <!-- 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 ea_robot_description)/meshes/propeller.dae"/>

  <!--
    Thruster macro with integration of joint and link. The thrusters should
    be initialized in the actuators.xacro file.
  -->
  <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>

        <!-- Make the thruster aware of its id -->
        <thrusterID>${thruster_id}</thrusterID>

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

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

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

        <!-- Minimum and maximum thrust force output allowed -->
        <thrustMin>0</thrustMin>
        <thrustMax>2000</thrustMax>

        <!--
        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.

        -->

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

        <!-- 2) First order model -->
        <dynamics>
          <type>FirstOrder</type>
          <timeConstant>0.05</timeConstant>
        </dynamics>

        <!-- 3) Yoerger's nonlinear dynamic model
        For information on the model description:
        [1] 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> -->

        <!-- 4) Bessa's nonlinear dynamic model
        For information on the model description:
        [2] 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

        -->

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

        <!-- 2) 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> -->

        <!-- 3) 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>

  <!--

  MACRO FOR FIN/RUDDER UNITS  

  -->

  <!--
    This macro can be used to add fins to the body of the vehicle, the fins
    should be initialized in the actuators.xacro file. If you vehicle has no
    fins, you can erase the macro below.
  -->

  <!-- A separate mesh for the fin should be stored in the meshes folder -->
  <xacro:property name="fin_mesh_file" value="file://$(find ea_robot_description)/meshes/fin.dae"/>

  <!-- Fin joint limits  -->
  <xacro:property name="fin_min_joint_limit" value="${0.0 * d2r}"/>
  <xacro:property name="fin_max_joint_limit" value="${0.0 * d2r}"/>

  <xacro:macro name="fin_macro" params="namespace fin_id *origin">
      <joint name="${namespace}/fin${fin_id}_joint" type="revolute">
          <limit effort="0" lower="${fin_min_joint_limit}" upper="${fin_max_joint_limit}" velocity="0"/>
          <xacro:insert_block name="origin"/>
          <axis xyz="0 0 1"/>
          <parent link="${namespace}/base_link" />
          <child link="${namespace}/fin${fin_id}" />
      </joint>

      <link name="${namespace}/fin${fin_id}">
        <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>
        <visual>
          <origin xyz="0 0 0" rpy="0 0 0" />
          <geometry>
            <mesh filename="${fin_mesh_file}" scale="1 1 1"/>
          </geometry>
        </visual>
      </link>

      <gazebo>
        <plugin name="${namespace}_fin${fin_id}_model" filename="libfin_ros_plugin.so">

          <!--

            First order dynamics model for the fin joint dynamics,
            replace an appropriate time constant

          -->
          <dynamics>
            <type>FirstOrder</type>
            <timeConstant>0.0</timeConstant>
          </dynamics>

          <!--

            Definition of the lift and drag model, choose ONE of the models
            below according to the model you want to use.

          -->

          <!--
            1) References for the two line lift and drag model:
              [1] https://en.wikipedia.org/wiki/Lift_coefficient
              [2] http://gazebosim.org/tutorials?tut=aerodynamics&cat=plugins
          -->
          <liftdrag>
            <type>TwoLines</type>
            <area>${replace here the value for the area of the fin's cross section}</area>
            <fluid_density>0.0</fluid_density>
            <a0>0.0</a0>
            <alpha_stall>0.0</alpha_stall>
            <cla>0.0</cla><!-- ^= 0.244 when using deg -->
            <cla_stall>0.0</cla_stall>
            <cda>0.0</cda>
            <cda_stall>0.0</cda_stall>
          </liftdrag>

          <!--
            2) Reference for the quadratic lift and drag model:
              [1] Engelhardtsen, Oystein. 3D AUV Collision Avoidance.
                  MS thesis. Institutt for teknisk kybernetikk, 2007.
                  https://brage.bibsys.no/xmlui/handle/11250/259834
          -->
          <liftdrag>
            <type>Quadratic</type>
            <lift_constant>0.0</lift_constant>
            <drag_constant>0.0</drag_constant>
          </liftdrag>

          <!--

            Further parameters necessary for the lift and drag plugin

          -->

          <!-- Current velocity topic -->
          <current_velocity_topic>/hydrodynamics/current_velocity</current_velocity_topic>

          <!-- Name of the correspodent fin link and joint  -->
          <link_name>${namespace}/fin${fin_id}</link_name>
          <joint_name>${namespace}/fin${fin_id}_joint</joint_name>

          <!-- Output topic to publish the current angle of the fin joint -->
          <output_topic>${namespace}/fins/${fin_id}/output</output_topic>
          <input_topic>${namespace}/fins/${fin_id}/input</input_topic>
          <wrench_topic>${namespace}/fins/${fin_id}/wrench_topic</wrench_topic>
        </plugin>
      </gazebo>
  </xacro:macro>

</robot>
musamarcusso commented 6 years ago

Hi @touhid1259, thanks for the information! I found a bug on the computation of the nonlinear damping coefficients for the sphere model related to a refactoring that happened a while ago. I am working on a patch and will notify you when it is finished.

musamarcusso commented 6 years ago

Hi @touhid1259, the damping problem should be solved for the sphere computation, could you check if it works?

touhid1259 commented 6 years ago

Hi musamarcusso

After I pulling the new code, I am getting an error for catkin_make install command. The error is:-

CMake Error at uuv_simulator/uuv_gazebo_plugins/uuv_gazebo_plugins/cmake_install.cmake:179 (file):
  file INSTALL cannot find
  "/home/touhid/catkin_ws_UUV/src/uuv_simulator/uuv_gazebo_plugins/uuv_gazebo_plugins/test".
Call Stack (most recent call first):
  cmake_install.cmake:135 (include)

Makefile:61: recipe for target 'install' failed
make: *** [install] Error 1
Invoking "make install -j4 -l4" failed

So, do I have to clone the repository again? Please, provide me any suggestion.

Thanks Touhid

musamarcusso commented 6 years ago

Hi @touhid1259, I found the mistake and will put a patch to that soon. I usually use the workspace configuration described in the documentation and therefore the error didn't show up to me.

musamarcusso commented 6 years ago

Hi @touhid1259, I recently merged the fix for that issue, do you still see the same error?

touhid1259 commented 6 years ago

Hi musamarcusso

Thanks for the fix. It is working perfectly now. Also, the robot is working as expected. I have couple of questions though. These are:

  1. Can you please tell me how am I suppose to calculate the "hydrodynamic parameters" i.e., added_mass and damping parameters for different kind of robots i.e., robots other than "spherical shape" or the added robots in the tutorial?

  2. Can I accelerate the simulation in gazebo i.e., simulating "10 mins in real time" with 2 mins?

I know Q#2 doesn't really concern this uuv simulator tool. Actually, I am trying to achieve that with uuv simulator and googled a bit to know more about it. But still not convinced or rather say fully understand about accelerating real time in simulation in gazebo. So, I am just asking for suggestions. It will be really helpful for me if you could provide some suggestions about these two questions.

And again thanks for the hotfix. It is working smoothly now.

Thanks Touhid

musamarcusso commented 6 years ago

Hi @touhid1259, I am glad that the issue is solved. Regarding your questions:

  1. There are ways of calculating the added-mass and damping coefficients by using approximations to simple shapes (for example, cylinders, spheres and so on). A few sources come to mind for me where you might find the correct equations to do that:

The spherical shape is simple but there is no damping in roll, pitch and yaw. Therefore it might lead to some unwanted behavior. But I think you will find more derivations in the material above.

  1. You can accelerate the simulation by changing this parameter in the world file, or go to the Gazebo GUI on the left side, click on "Physics" and change the parameters for "real time update" and "max step size". Be careful that the simulation can start to become unstable when you do that, depending on the parameters you are using.
touhid1259 commented 6 years ago

Hi musamarcusso

Thanks for the suggestions.

regards touhid