Model spawning incorrectly in Gazebo despite looking good in Rviz
I am trying to import a custom robot into gazebo. I designed it in solidworks, used the urdf converter and copied the package into the ROS workspace. The robot appears just fine in Rviz and all the joints are working they way they're supposed to. However, when I run the launch file for gazebo, the robot spawns as show in the figure below. I don't know what could be causing that kind of behaviour. I'm using ROS Indigo with Gazebo 2.2.6.
Thanks in advance
Here's the urdf file if anyone wants to take a look.
<robot name="manipulator" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find manipulator)/urdf/manipulator.gazebo"/>
<link name="world"/>
<joint name="fix" type="fixed">
<parent link="world"/>
<child link="base_link"/>
</joint>
<link name="base_link">
<inertial>
<origin xyz="-0.018218 3.767E-08 0.066046" rpy="0 0 0"/>
<mass value="1.1901"/>
<inertia ixx="0.0020853" ixy="-8.1652E-10" ixz="-0.00068251" iyy="0.002344" iyz="6.9296E-10" izz="0.00025871"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://manipulator/meshes/base_link.STL"/>
</geometry>
<material name="">
<color rgba="0.75294 0.75294 0.75294 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://manipulator/meshes/base_link.STL"/>
</geometry>
</collision>
</link>
<link name="link1">
<inertial>
<origin xyz="-1.7313E-06 0.016337 0.1197" rpy="0 0 0"/>
<mass value="0.18815"/>
<inertia ixx="0.00035983" ixy="1.5974E-08" ixz="9.0583E-09" iyy="0.00021667" iyz="-7.3319E-05" izz="0.00014318"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://manipulator/meshes/link1.STL"/>
</geometry>
<material name="">
<color rgba="0.75294 0.75294 0.75294 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://manipulator/meshes/link1.STL"/>
</geometry>
</collision>
</link>
<joint name="waist" type="revolute">
<origin xyz="0 0 0.0705" rpy="-2.8368E-15 2.3227E-18 0.0008188"/>
<parent link="base_link"/>
<child link="link1"/>
<axis xyz="0 0 1"/>
<limit lower="-3.14" upper="3.14" effort="2.8" velocity="1.1"/>
</joint>
<link name="link2">
<inertial>
<origin xyz="0.098154 0.02219 -0.00049839" rpy="0 0 0"/>
<mass value="0.2538"/>
<inertia ixx="0.000289" ixy="0.00092316" ixz="0.00012104" iyy="0.0057134" iyz="-1.4321E-05" izz="0.0058253"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://manipulator/meshes/link2.STL"/>
</geometry>
<material name="">
<color rgba="0.75294 0.75294 0.75294 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://manipulator/meshes/link2.STL"/>
</geometry>
</collision>
</link>
<joint name="shoulder" type="revolute">
<origin xyz="0 0 0.1475" rpy="1.5708 1.0989E-14 1.0298E-13"/>
<parent link="link1"/>
<child link="link2"/>
<axis xyz="0 0 1"/>
<limit lower="-0.13" upper="1.11" effort="2.8" velocity="1.1"/>
</joint ...
If you start the simulation paused, does the robot look ok before the simulation is played? This looks like an error on the dynamics specification of the robot. Do you see any errors when running on verbose mode?
@chapulina, The robot looks fine before the simulation is started. I don't really see anything in verbose mode either. Gazebo also throws an error saying it couldn't fine resource in the hardware_interface::EffortJointInterface despite having a <transmission> element in the urdf.
One way to debug would be to add one link at a time to the robot and see which link makes it collapse. Then investigate whether there are any errors on the dynamic and kinematic properties of that link.
@chapulina, I did what you said and added one link at a time. The second to last link makes the model collapse. The last two links are much lighter than the preceding 4 links, Do you think this difference may be destabilizing the model? If so, what can be done to remedy that?
humm yeah I think big inertia ratios between 2 links connected by a joint can confuse the physics engine sometimes. Not sure if there is a solution other than altering the inertia to be a big bigger. Out of curiosity, have you tried a physics engine different from the default (ODE)?
@chapulina, looks like I found the issue. There was some error when the model was created in solidworks and there wasn't an inertia tensor for the second last link. Therefore, it was running into problems. However, now I get an error saying
Could not find resource '\<jointname>' in 'hardware_interface::EffortJointInterface'
for every joint.But is the model still collapsing?
Nope. The model is fine now that I've fixed the inertia tensor.
Phew, it sounds like we're out of the Gazebo realm though, do you know who's asking for that resource?
Well, we're not entirely out of the gazebo realm. that's a resource related to the <transmission> tags in the urdf. http://gazebosim.org/tutorials/?tut=ros_control#Addthegazebo_ros_controlplugin