ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Continuous Joint will not load in Gazebo

asked 2017-06-07 14:01:57 -0500

RobRos gravatar image

I am following the structure of the R2D2 robot. I have structured my wheels exactly the same way.

(the github containing reference code to R2D2 wheels) https://github.com/albertodesouza/r2d...

Unfortunately, I can't get continuous joints to render in Gazebo. If I switch my joint type to "fixed" everything is loaded into Gazebo but, "continuous" prevents it from loading.

No errors are thrown, using check_urdf on my URDF file shows no problems. I am very confused as to what is going on.

I assume that the only thing a continuous joint needs in addition to the fixed joint requirements is an axis description.

Here is my code below:

<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="pad">

<!-- World Params -->
<xacro:property name="PI" value="3.14159"/>

<!-- Landing Pad Params -->
<xacro:property name="pad_length" value="1" />
<xacro:property name="pad_width" value ="0.1"/>

<!-- Wheel Params -->
<xacro:property name="wheel_length" value=".03" />
<xacro:property name="wheel_radius" value ="${2*pad_width}"/>

<!-- Inertial Macro -->
<xacro:macro name="default_inertial" params="mass">
    <inertial>
        <mass value="${mass}"/>
        <inertia ixx="1.0" ixy="0.0" ixz="0.0"
                         iyy="1.0" iyz="0.0" 
                         izz="1.0" />
  </inertial>
</xacro:macro>

<!-- Macro For Wheels -->
<xacro:macro name="wheel" params="prefix suffix r l x y z">

    <link name="${prefix}_${suffix}_wheel">
        <visual>
            <origin xyz="0 0 0" rpy="${PI/2} 0 0"/>
            <geometry>
                <cylinder length="${wheel_length}" radius="${wheel_radius}"/>
            </geometry>
            <origin xyz="0 0 0" rpy="0 0 0"/>
        </visual>
        <collision>
            <origin xyz="0 0 0" rpy="${PI/2} 0 0"/>
            <geometry>
                <cylinder length="${wheel_length}" radius="${wheel_radius}"/>
            </geometry>
            <origin xyz="0 0 0" rpy="$0 0 0"/>
        </collision>
        <xacro:defualt_inertial mass="1"/>
    </link>

    <joint name="${prefix}_${suffix}_wheel_joint" type="continuous">
        <parent link="base_link"/>
        <child link="${prefix}_${suffix}_wheel"/>
        <origin rpy="0 0 0" xyz="${x} ${y} ${z}"/>
        <axis xyz="0 1 0" rpy="0 0 0"/>
    </joint>

    <transmission name="${prefix}_${suffix}_wheel_trans" type="SimpleTransmission">
        <type>transmission_interface/SimpleTransmission</type>
        <joint name="${prefix}_${suffix}_wheel_joint">
            <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
            <mechanicalReduction>1</mechanicalReduction>
        </joint>
        <actuator name="${prefix}_${suffix}_wheel_motor">
            <hardwareInterface>EffortJointInterface</hardwareInterface>
            <mechanicalReduction>1</mechanicalReduction>
        </actuator>
    </transmission>
</xacro:macro>

<!-- Creating the Chassis (base_link) -->
<link name="base_link">
    <visual>
        <origin rpy="0 0 0" xyz="0 0 ${pad_width}"/>
        <geometry>
            <box size="${pad_length} ${pad_length} ${pad_width}"/>
        </geometry>
    </visual>
    <collision>
        <geometry>
            <box size="${pad_length} ${pad_length} ${pad_width}"/>
        </geometry>
    </collision>
    <xacro:default_inertial mass="10"/>
</link>

<!-- Creating Base Footprint -->
<link name="base_footprint"/>

<!-- Linking Base Foot to base_link -->
<joint name="base_footprint_joint" type="fixed">
    <origin xyz="0 0 0"/>
    <parent link="base_link"/>
    <child link="base_footprint"/>
</joint>

<!-- Adding Wheel Objects -->
<xacro:wheel prefix="front" suffix="left"  r="${wheel_radius}" l="${wheel_length}" x="${(pad_length-2*wheel_radius)/2}"  y=" ${-(pad_length+wheel_length+.1)/2}" z=".1"/>
<xacro:wheel prefix="front" suffix="right" r="${wheel_radius}" l="${wheel_length}" x="${(pad_length-2*wheel_radius)/2}"  y=" ${(pad_length+wheel_length+.1)/2}"  z=".1"/>
<xacro:wheel prefix="back"  suffix="right" r="${wheel_radius}" l="${wheel_length}" x="${-(pad_length-2*wheel_radius)/2}" y=" ${(pad_length+wheel_length+.1)/2}"  z=".1"/>
<xacro:wheel prefix="back"  suffix="left"  r="${wheel_radius}" l="${wheel_length}" x="${-(pad_length-2 ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2017-06-07 15:21:42 -0500

RobRos gravatar image

I found the problem. Looking through the produced URDF file I found the inertial macro was not called properly (typo).

So there was no inertial, fixed would work but continuous would not.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2017-06-07 14:01:57 -0500

Seen: 1,948 times

Last updated: Jun 07 '17