Pose and orientation of my robot is incorrect in Gazebo
I have exported the URDF from Solidworks using solidworks to URDF plugin. I didn't modify any option in dialogues opened during export. Then i created an URDF package in ROS workspace and spawned the robot model into the world which resulted in inverted pose of the robot as shown in picture.
Following is my URDF file, where have i gone wrong and how to patch it up.
<robot
name="JMbot">
<link
name="Base_plate">
<inertial>
<origin
xyz="-0.3317 -0.71959 -0.39019"
rpy="0 0 0" />
<mass
value="0.55378" />
<inertia
ixx="0.0061249"
ixy="0.00016086"
ixz="-8.6651E-18"
iyy="0.0041631"
iyz="-1.4656E-17"
izz="0.010283" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://jmbot_description/meshes/Base_plate.STL" />
</geometry>
<material
name="">
<color
rgba="0.74902 0.74902 0.74902 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://jmbot_description/meshes/Base_plate.STL" />
</geometry>
</collision>
</link>
<link
name="Wheel_R">
<inertial>
<origin
xyz="0.010951 1.1102E-16 -1.1102E-16"
rpy="0 0 0" />
<mass
value="0.45064" />
<inertia
ixx="0.00091608"
ixy="-1.2355E-19"
ixz="1.0715E-18"
iyy="0.00053395"
iyz="-6.7763E-20"
izz="0.00053395" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://jmbot_description/meshes/Wheel_R.STL" />
</geometry>
<material
name="">
<color
rgba="0.74902 0.74902 0.74902 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://jmbot_description/meshes/Wheel_R.STL" />
</geometry>
</collision>
</link>
<joint
name="Wheel_R"
type="continuous">
<origin
xyz="-0.14688 0.40756 -0.73464"
rpy="-2.7127 -0.081268 -3.1416" />
<parent
link="Base_plate" />
<child
link="Wheel_R" />
<axis
xyz="1 0 0" />
</joint>
<link
name="Wheel_L">
<inertial>
<origin
xyz="-0.039049 2.2204E-16 2.498E-15"
rpy="0 0 0" />
<mass
value="0.45064" />
<inertia
ixx="0.00091608"
ixy="-9.6693E-19"
ixz="-1.7816E-18"
iyy="0.00053395"
iyz="1.3553E-19"
izz="0.00053395" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://jmbot_description/meshes/Wheel_L.STL" />
</geometry>
<material
name="">
<color
rgba="0.74902 0.74902 0.74902 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://jmbot_description/meshes/Wheel_L.STL" />
</geometry>
</collision>
</link>
<joint
name="Wheel_L"
type="continuous">
<origin
xyz="-0.46668 0.40756 -0.70859"
rpy="2.512 0.081268 3.4272E-15" />
<parent
link="Base_plate" />
<child
link="Wheel_L" />
<axis
xyz="-1 0 0" />
</joint>
<link
name="Castor_F">
<inertial>
<origin
xyz="2.2204E-16 0 0.031164"
rpy="0 0 0" />
<mass
value="0.056555" />
<inertia
ixx="2.4476E-05"
ixy="-2.8588E-35"
ixz="1.0281E-20"
iyy="2.4476E-05"
iyz="-1.2617E-20"
izz="7.4341E-06" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://jmbot_description/meshes/Castor_F.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://jmbot_description/meshes/Castor_F.STL" />
</geometry>
</collision>
</link>
<joint
name="Castor_F"
type="continuous">
<origin
xyz="-0.31952 0.39256 -0.57008"
rpy="-1.5708 1.1481 -1.3614E-16" />
<parent
link="Base_plate" />
<child
link="Castor_F" />
<axis
xyz="0 0 1" />
</joint>
<link
name="Castor_R">
<inertial>
<origin
xyz="-1.1102E-16 0 0.031164"
rpy="0 0 0" />
<mass
value="0.056555" />
<inertia
ixx="2.4476E-05"
ixy="0"
ixz="-3.9352E-20"
iyy="2.4476E-05"
iyz="-1.951E-20"
izz="7.4341E-06" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://jmbot_description/meshes/Castor_R.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://jmbot_description/meshes/Castor_R.STL" />
</geometry>
</collision>
</link>
<joint
name="Castor_R"
type="continuous">
<origin
xyz="-0.34387 0.39256 -0.86909"
rpy="1.5708 -0.93144 3.1416" />
<parent
link="Base_plate" />
<child
link="Castor_R" />
<axis
xyz="0 0 1" />
</joint>
</robot>
Asked by KishoreKumar P on 2015-12-17 12:41:45 UTC
Answers
There are a lot of mechanisms in Gazebo to debug models. Try a few of these:
Start gazebo paused using the
-u
command line argument. This will allow you to see the model before physics kicks-in.Visualize joints, collision shapes, mass, etc. Use these visualizations to make sure that everything is in the correct place.
Make small changes to your model file, and reload it into Gazebo until you get your model the way you want it.
Asked by nkoenig on 2015-12-17 12:54:02 UTC
Comments
After a brief play with urdf file i fixed it. I inverted the sign of base_plate origin's Y co-ordinate.
Error:
<inertial>
<origin
xyz="-0.3317 -0.71959 -0.39019"
rpy="0 0 0" />
Solution:
<inertial>
<origin
xyz="-0.3317 0.71959 -0.39019"
rpy="0 0 0" />
Asked by KishoreKumar P on 2015-12-29 08:53:47 UTC
Comments