Gazebo urdf model joint link error
Hi,
I am working in gazebo on a urdf robot model and would like to attach a manipulator. This manipulator consists of a simple link which is attached to the robot (${namespace}/base_link) via a revolute joint. When I launch the basic robot platform without manipulator, everything is working fine. However, as soon as I add the manipulator link and manipulator_joint1, gazebo crashes. It claims to write the error in the logfile
~/.ros/..../gazebo-1.log
However, this logfile does not exist (I was checking in the complete /.ros log directory)!? Do you have any suggestions, how I can debug the gazebo urdf model, written in xacro? If not, do you have any idea, what could be wrong in the implementation? Thanks a lot! This is the minimal example that I am using
<robot name="robot_with_arm" xmlns:xacro="http://ros.org/wiki/xacro">
<!-- For the manipulator -->
<xacro:property name="manipulator_link_length" value="2" /> <!-- Link 1 -->
<xacro:property name="manipulator_link_width" value="0.02" /> <!-- Link 1 -->
<xacro:property name="manipulator_link_mass" value="0.2" /> <!-- Link 1 -->
... <!-- Here the robot is defined with ${namespace}/base_link -->
<!-- Link -->
<link name="${namespace}/manipulator_link">
<collision>
<origin xyz="${manipulator_link_length}/2 0.0 0.0" rpy="0 0 0"/>
<geometry>
<box size="${manipulator_link_length} {manipulator_link_width} ${manipulator_link_width} "/>
</geometry>
</collision>
<visual>
<origin xyz="${manipulator_link_length}/2 0.0 0.0" rpy="0 0 0"/>
<geometry>
<box size="{manipulator_link_length} ${manipulator_link_width} ${manipulator_link_width} "/>
</geometry>
<material name="black"/>
</visual>
<inertial>
<origin xyz="${manipulator_link_length}/2 0.0 0.0" rpy="0 0 0"/>
<mass value="${manipulator_link_mass}"/>
<inertia
ixx="${manipulator_link_mass / 3 * (manipulator_link_width*manipulator_link_width + manipulator_link_width*manipulator_link_width)}" ixy="0.0" ixz="0.0"
iyy="${manipulator_link_mass / 3 * (manipulator_link_length*manipulator_link_length + manipulator_link_width*manipulator_link_width)}" iyz="0.0"
izz="${manipulator_link_mass / 3 * (manipulator_link_width*manipulator_link_width + manipulator_link_length*manipulator_link_length)}"/>
</inertial>
</link>
<!-- Joint -->
<joint name="manipulator_joint1" type="revolute">
<parent link="${namespace}/base_link"/>
<child link="${namespace}/manipulator_link"/>
<origin xyz="0.0 0.0 0.0" rpy="0.0 ${-pi/2} 0.0"/>
<axis xyz="0.0 1.0 0.0"/>
<limit lower="-3.141526/2" upper="0"/>
<dynamics damping="0.7"/>
</joint>
</robot>
Can you show us the error (the ouput of the terminal command that results in Gazebo crashing) ? When you set a
revolute
joint you have to add the required taglimit
(which you've done) but inside you also have required attributes :effort
andvelocity
....... see the wiki for details. Also have you seen #q48796 ? That might be the same issue.
LOL, you are completely right. If I use <limit effort="100" velocity="100"/> there is no problem at all -.- . Thanks a lot!!!