Urdf displays correcly in urdf-viz but not Rviz and Gazebo
Hello Everyone
New to ROS and i'm trying to import a CAD model via simmechanics_to_urdf.
If i open the urdf in urdf-viz ( https://github.com/OTL/urdf-viz ) i get a proper model and can move the joints.
However if i open the same urdf and meshes in either Rviz or Gazebo the parts show up in strange positions. (mostly around the origin).
edit: seems the issue was at least in part the lack of a fixed joint at the base to apparently anchor the model. As soon as I added a fixed base joint everything started working in Rviz. Gazebo still has the same issue. urdf-viz does not require the fixed base joint so it would display correctly regardless
Any ideas? Sorry i don't have a better vocabulary to explain the issue.
<robot name="finger">
<link name="base_link" />
<link name="base8">
<inertial>
<origin xyz="-1.26773e-06 0.000427739 0.00546823" rpy="0 0 0"/>
<mass value="0.00171993"/>
<inertia ixx="4.15282e-08" ixy="3.76912e-12" ixz="3.81441e-12" iyy="9.2702e-08" iyz="-1.64114e-09" izz="9.15731e-08"/>
</inertial>
<visual>
<origin xyz="0 0 0.0114743" rpy="0 0 0"/>
<geometry>
<mesh filename="package://finger_description/meshes/base8_ipt_11dce11d.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="base8_color">
<color rgba="0.74902 0.74902 0.74902 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0.0114743" rpy="0 0 0"/>
<geometry>
<mesh filename="package://finger_description/meshes/base8_ipt_11dce11d.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<link name="finger_segment1">
<inertial>
<origin xyz="0.00449723934 0.00021284299985 0.0071977" rpy="0 0 0"/>
<mass value="0.00199166"/>
<inertia ixx="1.06576e-07" ixy="1.37509e-11" ixz="3.64504e-11" iyy="1.21654e-07" iyz="-3.77147e-09" izz="5.43651e-08"/>
</inertial>
<visual>
<origin xyz="0.0045 -1.77523001664e-05 0.008" rpy="0 0 0"/>
<geometry>
<mesh filename="package://finger_description/meshes/finger_segment_ipt_544d6e46.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="finger_segment1_color">
<color rgba="0.74902 0.74902 0.74902 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0.0045 -1.77523001664e-05 0.008" rpy="0 0 0"/>
<geometry>
<mesh filename="package://finger_description/meshes/finger_segment_ipt_544d6e46.stl" scale="0.001 0.001 0.001"/>
</geometry>
</collision>
</link>
<joint name="finger_segment1__base8" type="continuous">
<origin xyz="-0.0045 0 0.0114743" rpy="0 0 0"/>
<axis xyz="1.0 0.0 0.0"/>
<parent link="base8"/>
<child link="finger_segment1"/>
<dynamics damping="0.1"/>
</joint>
<link name="finger_segment2">
<inertial>
<origin xyz="0.00449723934 0.000212842999506 0.0071977" rpy="0 0 0"/>
<mass value="0.00199166"/>
<inertia ixx="1.06576e-07" ixy="1.37509e-11" ixz="3.64504e-11" iyy="1.21654e-07" iyz="-3.77147e-09" izz="5.43651e-08"/>
</inertial>
<visual>
<origin xyz="0.0045 -1.77523005075e-05 0.008" rpy="0 0 0"/>
<geometry>
<mesh filename="package://finger_description/meshes/finger_segment_ipt_544d6e46.stl" scale="0.001 0.001 0.001"/>
</geometry>
<material name="finger_segment2_color">
<color rgba="0.74902 0.74902 0.74902 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0.0045 -1.77523005075e-05 0.008" rpy="0 0 0"/>
<geometry>
<mesh ...
I seem to remember that the urdfs coming out of that tool are not always entirely correct, leading to problems when you try to use them with ROS without any post-processing.
Without seeing your urdf we cannot help you I'm afraid.
Please copy-paste it into your question, use the
edit
button/link.this could actually point to a different problem.
How are you "open[ing] the same urdf in [..] Rviz" exactly? Which commands do you use?
Hi gvdhoorn.
To launch in Rviz i use:
To launch in gazebo i run:
I based my test in tutorials i found online. Just kept the robot name and just filled in my urdf (now in main answer). Thank You
Just a quick comment:
I'm not sure names with colons in them are actually legal in ROS. See wiki/Names.
Removed all colons in names. Results are the same.