URDF model not appearing in Rviz nor Gazebo
i have been trying to open in gazebo and rviz a URDF file of a double pendulum that i have designed in solidworks and exported the URDF code using the URDF exporter. i am facing problems in visualizing my project in gazebo and rviz. The environments appear to be empty although the panels on the left indicate that all the link exist along with their properties. i can conclude from the position and orientation of the coordinate frames of each link that the scale of the robot is very small and in rviz a message appears indicating that the links have NO geometry.
Kindly check the URDF code below:
<?xml version="1.0" encoding="utf-8"?>
<!-- This URDF was automatically created by SolidWorks to URDF Exporter! Originally created by Stephen Brawner (brawner@gmail.com)
Commit Version: 1.5.1-0-g916b5db Build Version: 1.5.7152.31018
For more information, please see http://wiki.ros.org/sw_urdf_exporter -->
<robot
name="base_2links">
<link
name="base_link">
<inertial>
<origin
xyz="-0.016 0.0034506 0.074794"
rpy="0 0 0" />
<mass
value="0.027215" />
<inertia
ixx="2.0815E-06"
ixy="3.1439E-22"
ixz="-2.2393E-22"
iyy="1.2394E-05"
iyz="-1.2756E-22"
izz="1.2544E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://base_2links/meshes/base_link.STL" />
</geometry>
<material
name="">
<color
rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://base_2links/meshes/base_link.STL" />
</geometry>
</collision>
</link>
<link
name="link1">
<inertial>
<origin
xyz="-0.00035493 0.020275 -0.012885"
rpy="0 0 0" />
<mass
value="0.014265" />
<inertia
ixx="4.1101E-06"
ixy="5.9474E-08"
ixz="1.4157E-23"
iyy="7.1379E-07"
iyz="-1.3929E-23"
izz="4.2611E-06" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://base_2links/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://base_2links/meshes/link1.STL" />
</geometry>
</collision>
</link>
<joint
name="joint1"
type="continuous">
<origin
xyz="-0.016 -0.062794 0.013249"
rpy="1.5708 0.017504 -3.1416" />
<parent
link="base_link" />
<child
link="link1" />
<axis
xyz="0 0 1" />
</joint>
<link
name="link2">
<inertial>
<origin
xyz="0.014984 0.013663 -0.0038295"
rpy="0 0 0" />
<mass
value="0.014265" />
<inertia
ixx="2.2556E-06"
ixy="-1.692E-06"
ixz="4.6898E-22"
iyy="2.5683E-06"
iyz="5.9919E-22"
izz="4.2611E-06" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://base_2links/meshes/link2.STL" />
</geometry>
<material
name="">
<color
rgba="0.75294 0.75294 0.75294 1" /> ...