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

Fixed urdf object in Gazebo

asked 2011-10-27 21:18:45 -0500

erkmns gravatar image

Hi,

I`m trying to get a fixed object in Gazebo, meaning it can not be moved by exerting forces on it.
The urdf looks like this:

<link name="world"/>

<joint name="pallet_joint" type="floating">
    <parent link="world"/>
    <origin rpy="0 0 0" xyz="0 0 0"/>
    <child link="pallet_body"/>
</joint>

<link name="pallet_body">
    <inertial>
        <mass value="10.0"/>
        <origin rpy="0 0 0" xyz="0 0 0"/>
        <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="0.1" iyz="0.0" izz="0.1"/>
    </inertial>
    <visual>
        <origin rpy="0 0 0 " xyz="0 0 0"/>
        <geometry>
            <box size="0.8 1.2 0.15"/>
        </geometry>
    </visual>
    <collision>
        <origin rpy="0 0 0" xyz="0 0 0"/>
        <geometry>
            <box size="0.8 1.2 0.15"/>
        </geometry>
    </collision>
</link>

The launch file looks like this:

<?xml version="1.0"?>
<launch>
    <param name="pallet" textfile="$(find gazebo_tests)/pallet.urdf" />
    <node name="spawn_pallet" pkg="gazebo" type="spawn_model" args="-urdf -param pallet -model pallet1 -x 5.0 -y 5.0 -z 0.5 " respawn="false" output="screen" />
</launch>

This works fine, but when I change the joint type to 'fixed' the pallet doesn't get spawned any more.

<joint name="pallet_joint" type="fixed">

Although 'pallet1' is displayed in the Models-list in Gazebo, it is no where to be seen. No errors get printed either.
(Changing the joint type to 'continuous' makes the pallet shake around at the origin - not at location '5.0 5.0 0.5' where it should be spawned.)

Any suggestions would be greatly appreciated!

Regards,
Eli

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
2

answered 2011-10-30 20:56:39 -0500

erkmns gravatar image

The previous answer did not solve the problem in my case, since the object could still be moved by exerting forces on it.

But following model file did the job for me:

<?xml version="1.0" ?>
<model:physical name="pallet" 
    xmlns:body="http://playerstage.sourceforge.net/gazebo/xmlschema/#body"
    xmlns:geom="http://playerstage.sourceforge.net/gazebo/xmlschema/#geom"
>

<static>true</static>

<body:box name="pallet_body">
    <xyz>  0   0.0  0.0</xyz>
    <rpy>   0.0    0.0    0.0</rpy>

    <geom:box name="base">   
        <mesh>default</mesh>
        <size> 1.2 0.8 0.05</size>  
        <visual>
            <size> 1.2 0.8 0.05</size>
            <material>Gazebo/WoodPallet</material>
            <mesh>unit_box</mesh>
        </visual>
        <collision>
            <size> 1.2 0.05 0.5</size>
        </collision>
    </geom:box>
</body:box>

</model:physical>

Launch file as follows:

<?xml version="1.0"?>
<launch>
    <param name="pallet" textfile="$(find gazebo_tests)/pallet.model" /> 
    <node name="spawn_pallet" pkg="gazebo" type="spawn_model" args="-param pallet -gazebo -model pallet1 -x 0.0 -y -0.8 -z 0.15" output="screen" /> 
</launch>
edit flag offensive delete link more

Comments

Can anyone verify if this method of fixing a base link in the world frame is still supported?

matthewmarkey gravatar image matthewmarkey  ( 2020-05-18 09:13:00 -0500 )edit
0

answered 2011-10-28 01:55:17 -0500

DimitriProsser gravatar image

Instead of fixing the model to the world frame with a joint, you could try to use the following code outside of the link block:

<link name="pallet_body">
    ...
</link>
<gazebo reference="pallet_body">
    <static>true</static>
    <turnGravityOff>true</turnGravityOff>
</gazebo>
edit flag offensive delete link more

Question Tools

Stats

Asked: 2011-10-27 21:18:45 -0500

Seen: 6,250 times

Last updated: Oct 30 '11