Robotics StackExchange | Archived questions

Origin of revolute joints don't move in Gazebo11

Hi,

Can someone help me please?

My URDF file have three revolute joints (rudderjoint, sailjoint, tail_joint) with origin defined:

<?xml version="1.0"?>

<xacro:property name="PI" value="3.1415926535897931"/>
<xacro:property name="scale" value="1"/>

<!--_______________________-->
<!--________ HULL _________-->
<!--_______________________-->
<link name="sailboat/base_link">
    <visual>
        <origin xyz="-0.79 0 0.26" rpy="0 0 0" />
        <geometry>
            <!--mesh filename="package://sailboat_description/models/meshes/hull_material.dae" scale="${scale} ${scale} ${scale}"/-->
            <mesh filename="package://sailboat_description/models/meshes/hull_material.dae" scale="${scale} ${scale} ${scale}"/>
        </geometry>
    </visual>

    <collision name="collision">
        <origin xyz="-0.79 0 0.26" rpy="0 0 0"/>
        <geometry>
            <mesh filename="package://sailboat_description/models/meshes/hull_origin.STL" scale="${scale} ${scale} ${scale}"/>
        </geometry>
    </collision>

    <!-- Mass is calculated based on an estimate of draft, the effective length and the cross-section of
    a circle segment. The value for the draft is consistent specifications of similar vessels.  Moments of inertia are based on an effective cylindrical model-->
    <inertial>
        <mass value="184.04"/>
        <inertia ixx="5.99" ixy="0.0" ixz="0.0" iyy="230.06" iyz="0.0" izz="235.86"/>
        <origin xyz="-0.79 0 0.26" rpy="0 0 0"/>
    </inertial>
</link>


<!--_______________________-->
<!--_______ RUDDER ________-->
<!--_______________________-->
<link name="sailboat/rudder_link">
    <visual name="visual">
        <geometry>
            <!--mesh filename="package://sailboat_description/models/meshes/leme_material.dae" scale="${scale} ${scale} ${scale}"/-->
            <mesh filename="package://sailboat_description/models/meshes/leme_material.dae" scale="${scale} ${scale} ${scale}"/>
        </geometry>
        <!--origin xyz="-1.57 0 -0.21" rpy="0 0 0"/-->
        <origin xyz="0 0 0" rpy="0 0 0"/>
    </visual>

    <collision name="collision">
        <geometry>
            <mesh filename="package://sailboat_description/models/meshes/leme_origin.STL" scale="${scale} ${scale} ${scale}"/>
        </geometry>
        <!--origin xyz="-1.57 0 -0.21" rpy="0 0 0"/-->
        <origin xyz="0 0 0" rpy="0 0 0"/>
    </collision>

    <inertial>
        <mass value="1.39" />
        <inertia ixx="0.03" ixy="0.0" iyy="0.03" ixz="0.0" iyz="0.0" izz="0.01" />
        <!--origin xyz="-1.57 0 -0.21" rpy="0 0 0"/-->
        <origin xyz="0 0 0" rpy="0 0 0"/>
    </inertial>
</link>

<joint name="sailboat/rudder_joint" type="revolute">
    <parent link="sailboat/base_link"/>
    <child link="sailboat/rudder_link"/>
    <origin xyz="-1.57 0 -0.21" rpy="0 0 0"/>
    <dynamics damping="1.0"/>
    <axis xyz="0 0 1"/>
    <limit effort="100" velocity="5" lower="-${PI/2}" upper="${PI/2}" />
</joint>


<!--_______________________-->
<!--________ KEEL _________-->
<!--_______________________-->
<link name="sailboat/keel_link">
    <visual name="visual">
        <geometry>
            <!--mesh filename="package://sailboat_description/models/meshes/keel_material.dae" scale="${scale} ${scale} ${scale}"/-->
            <mesh filename="package://sailboat_description/models/meshes/keel_material.dae" scale="${scale} ${scale} ${scale}"/>
        </geometry>
        <!--origin xyz="0.54 0 -0.91" rpy="0 0 0"/-->
        <origin xyz="0 0 0" rpy="0 0 0"/>
    </visual>

    <collision name="collision">
        <geometry>
            <mesh filename="package://sailboat_description/models/meshes/keel_origin.STL" scale="${scale} ${scale} ${scale}"/>
        </geometry>
        <!--origin xyz="0.54 0 -0.91" rpy="0 0 0"/-->
        <origin xyz="0 0 0" rpy="0 0 0"/>
    </collision>

    <inertial>
        <mass value="211.39" />
        <inertia ixx="34.28" ixy="0.0" iyy="44.11" ixz="0.0" iyz="0.0" izz="10.65"/>
        <!--origin xyz="0.54 0 -0.91" rpy="0 0 0"/-->
        <origin xyz="0 0 0" rpy="0 0 0"/>
    </inertial>
</link>

<!--joint name="sailboat/keel_joint" type="fixed">
    <parent link="sailboat/base_link"/>
    <child link="sailboat/keel_link"/>
    <origin xyz="0 0 0" rpy="0 0 0"/>
    <dynamics damping="1.0"/>
    <axis xyz="0 0 1"/>
    <limit effort="30" velocity="5" lower="0" upper="0" />
</joint-->

<joint name="sailboat/keel_joint" type="fixed">
    <parent link="sailboat/base_link"/>
    <child link="sailboat/keel_link"/>
    <origin xyz="0.54 0 -0.91" rpy="0 0 0"/>
</joint>


<!--_______________________-->
<!--________ SAIL _________-->
<!--_______________________-->
<link name="sailboat/sail_link">
    <visual name="visual">
        <geometry>
            <!--mesh filename="package://sailboat_description/models/meshes/wingsail_material.dae" scale="${scale} ${scale} ${scale}"/-->
            <mesh filename="package://sailboat_description/models/meshes/wingsail_material.dae" scale="${scale} ${scale} ${scale}"/>
        </geometry>
        <!--origin xyz="0.47 0 1.3" rpy="0 0 0"/-->
        <origin xyz="0 0 0" rpy="0 0 0"/>
    </visual>

    <collision name="collision">
        <geometry>
            <mesh filename="package://sailboat_description/models/meshes/wingsail_origin.STL" scale="${scale} ${scale} ${scale}"/>
        </geometry>
        <!--origin xyz="0.47 0 1.3" rpy="0 0 0"/-->
        <origin xyz="0 0 0" rpy="0 0 0"/>
    </collision>

    <inertial>
        <mass value="97.27" />
        <inertia ixx="32.57" ixy="0.0" iyy="46.70" ixz="0.0" iyz="0.0" izz="14.61"/>
        <!--origin rpy="0.47 0 1.3" xyz="0 0 0"/-->
        <origin xyz="0 0 0" rpy="0 0 0"/>
    </inertial>
</link>

<joint name="sailboat/sail_joint" type="revolute">
    <parent link="sailboat/base_link"/>
    <child link="sailboat/sail_link"/>
    <origin xyz="0.47 0 1.3" rpy="0 0 0"/>
    <dynamics damping="0"/>
    <axis xyz="0 0 1"/>
    <limit effort="100" velocity="70" lower="-${PI}" upper="${PI}" />
</joint>


<!--_______________________-->
<!--________ TAIL _________-->
<!--_______________________-->
<link name="sailboat/tail_link">
    <visual name="visual">
        <geometry>
            <!--mesh filename="package://sailboat_description/models/meshes/tail_material.dae" scale="${scale} ${scale} ${scale}"/-->
            <mesh filename="package://sailboat_description/models/meshes/tail_material.dae" scale="${scale} ${scale} ${scale}"/>
        </geometry>
        <!--origin xyz="-1.48 0 0.13" rpy="0 0 0"/-->
        <origin xyz="0 0 0" rpy="0 0 0"/>
    </visual>

    <collision name="collision">
        <geometry>
            <mesh filename="package://sailboat_description/models/meshes/tail_origin.STL" scale="${scale} ${scale} ${scale}"/>
        </geometry>
        <!--origin xyz="-1.48 0 0.13" rpy="0 0 0"/-->
        <origin xyz="0 0 0" rpy="0 0 0"/>
    </collision>

    <inertial>
        <mass value="11.69" />
        <inertia ixx="0.49" ixy="0.0" iyy="0.69" ixz="0.0" iyz="0.0" izz="0.2"/>
        <!--origin rpy="-1.48 0 0.13" xyz="0 0 0"/-->
        <origin xyz="0 0 0" rpy="0 0 0"/>
    </inertial>
</link>

<joint name="sailboat/tail_joint" type="revolute">
    <origin xyz="-1.48 0 0.13" rpy="0 0 0"/>
    <parent link="sailboat/sail_link"/>
    <child link="sailboat/tail_link"/>
    <dynamics damping="0"/>
    <axis xyz="0 0 1"/>
    <limit effort="10000" velocity="0" lower="-${PI}" upper="${PI}" />
</joint>

In RViz the joints origin position are correct as you can see on this image image description

,but in Gazebo joints don't move. image description

image description

Happens only with revolute and continuous joints. If type are fixed the joint and link go to correct place.

How should I set the origin of the revolute joints? To be correct in Gazebo and the RVIz?

Please help! Thank you

Asked by jpftavares on 2023-03-09 06:05:51 UTC

Comments

Are the links in the correct place before you start simulation, i.e, if you start paused?

Asked by azeey on 2023-03-09 23:17:53 UTC

Yes! If I start simulation paused the links are in correct place and the joints too!

Asked by jpftavares on 2023-03-10 05:28:57 UTC

Is it possible to be something related to usv_gazebo_dynamics_plugin?

Asked by jpftavares on 2023-03-10 05:35:00 UTC

I think that's possible. If for some reason, the plugin is commanding nan values to the joints, Gazebo tends to collapse the pose of every link to the origin. Can you try running it without the plugin first? Then check if the plugin is configured properly. Usually these kinds of issues happen if you have bad mass/inertia values, so I would check those as well, although, from a glance, yours looks okay to me.

Asked by azeey on 2023-03-10 13:59:08 UTC

Yes! Without plugin the simulation runs properly. I will check if the hydrodynamics parameters are correct. I don't know the specific parameters of my sailboat but i think the values I used aren't inappropriate. The plugin is this. The mass/inertia values I got directly from Solidworks, so I think that's are okay. Thanks for your help!

Asked by jpftavares on 2023-03-10 14:58:55 UTC

Confirmed! I changed the hydrodynamics parameters and works! Apparantely is some value of added mass... I don't konw...

Asked by jpftavares on 2023-03-10 20:51:57 UTC

By the way, if anyone wants to know what simulator i am using is VRX simulator

Asked by jpftavares on 2023-03-10 20:53:33 UTC

Great! glad to hear it's solved.

Asked by azeey on 2023-03-11 00:24:55 UTC

Answers