Robotics StackExchange | Archived questions

Cannot spawn Solidworks generated urdf model to gazebo.

Dear SIrs, I have tried all I know to spawn a model created using Solidworks to Gazebo for simulation. The urdf file has been exported using a tool for creating urdf files inside Soliworks.

The urdf file is the following:

<!--
 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="robot_urdf">
<link name="robot_base">
<inertial>
<origin xyz="0.152 -0.0625420962769482 0.00703464237079188" rpy="0 0 0"/>
<mass value="0.328439502632123"/>
<inertia ixx="0.00166317188204101" ixy="5.84339679477964E-19" ixz="1.91934869525446E-20" iyy="0.00265002456943154" iyz="0.000616470492128439" izz="0.00376104038840237"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://robot_urdf/meshes/robot_base.STL"/>
</geometry>
<material name="">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://robot_urdf/meshes/robot_base.STL"/>
</geometry>
</collision>
</link>
<joint name="j4" type="continuous">
<origin xyz="0.15591 -0.075981 -0.0035605" rpy="0.41868 0 3.1416"/>
<parent link="robot_base"/>
<child link="w4"/>
<axis xyz="1 0 0"/>
</joint>
<link name="w1">
<inertial>
<origin xyz="0.014 0 -3.4694E-18" rpy="0 0 0"/>
<mass value="0.061522"/>
<inertia ixx="5.5443E-05" ixy="8.9343E-21" ixz="-4.0706E-22" iyy="3.0092E-05" iyz="-5.0822E-21" izz="3.0092E-05"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://robot_urdf/meshes/w1.STL"/>
</geometry>
<material name="">
<color rgba="0.29804 0.29804 0.29804 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://robot_urdf/meshes/w1.STL"/>
</geometry>
</collision>
</link>
<joint name="j1" type="revolute">
<origin xyz="0.304 -0.109634968085994 0.0487870246354819" rpy="2.14240707483869 0 0"/>
<parent link="robot_base"/>
<child link="w1"/>
<axis xyz="1 0 0"/>
<limit lower="0" upper="0" effort="0" velocity="0"/>
</joint>
<link name="w2">
<inertial>
<origin xyz="-0.014 1.0408E-17 0" rpy="0 0 0"/>
<mass value="0.061522"/>
<inertia ixx="5.5443E-05" ixy="-1.8201E-20" ixz="6.2244E-21" iyy="3.0092E-05" iyz="-5.9292E-21" izz="3.0092E-05"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://robot_urdf/meshes/w2.STL"/>
</geometry>
<material name="">
<color rgba="0.29804 0.29804 0.29804 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://robot_urdf/meshes/w2.STL"/>
</geometry>
</collision>
</link>
<joint name="j2" type="revolute">
<origin xyz="-3.58147028304556E-05 -0.109634968085994 0.0487870246354823" rpy="-2.3203312160931 0 0"/>
<parent link="robot_base"/>
<child link="w2"/>
<axis xyz="1 0 0"/>
<limit lower="0" upper="0" effort="0" velocity="0"/>
</joint>
<link name="w3">
<inertial>
<origin xyz="0.014 -3.4694E-18 -1.3878E-17" rpy="0 0 0"/>
<mass value="0.061522"/>
<inertia ixx="5.5443E-05" ixy="6.5784E-21" ixz="-2.0743E-21" iyy="3.0092E-05" iyz="-1.1011E-20" izz="3.0092E-05"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://robot_urdf/meshes/w3.STL"/>
</geometry>
<material name="">
<color rgba="0.29804 0.29804 0.29804 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://robot_urdf/meshes/w3.STL"/>
</geometry>
</collision>
</link>
<joint name="j3" type="revolute">
<origin xyz="0.304 0 0" rpy="1.48802974926342 0 0"/>
<parent link="robot_base"/>
<child link="w3"/>
<axis xyz="1 0 0"/>
<limit lower="0" upper="0" effort="0" velocity="0"/>
</joint>
<link name="w4">
<inertial>
<origin xyz="-0.014 0 0" rpy="0 0 0"/>
<mass value="0.0615219544751675"/>
<inertia ixx="5.54433425808419E-05" ixy="9.27882825319427E-21" ixz="7.86127790599438E-22" iyy="3.00921775305435E-05" iyz="-1.6940658945086E-21" izz="3.00921775305435E-05"/>
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://robot_urdf/meshes/w4.STL"/>
</geometry>
<material name="">
<color rgba="0.298039215686275 0.298039215686275 0.298039215686275 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://robot_urdf/meshes/w4.STL"/>
</geometry>
</collision>
</link>
<joint name="j4" type="revolute">
<origin xyz="0 0 0" rpy="0 0 0"/>
<parent link="robot_base"/>
<child link="w4"/>
<axis xyz="1 0 0"/>
<limit lower="0" upper="0" effort="0" velocity="0"/>
</joint>
</robot>

The launch file is the following:

<launch>
  <include
    file="$(find gazebo_ros)/launch/empty_world.launch" />
  <node
    name="tf_footprint_base"
    pkg="tf"
    type="static_transform_publisher"
    args="0 0 0 0 0 0 base_link base_footprint 40" />
  <node
    name="spawn_model"
    pkg="gazebo_ros"
    type="spawn_model"
    args="-file $(find robot_urdf)/urdf/robot_urdf.urdf -urdf -model robot_urdf"
    output="screen" />
  <node
    name="fake_joint_calibration"
    pkg="rostopic"
    type="rostopic"
    args="pub /calibrated std_msgs/Bool true" />
</launch>

There are some mesh files included is a mesh directory in .STL format

The error message I get when running the launch command is the following:

Error [parser_urdf.cc:3408] Unable to call parseURDF on robot model Error [parser.cc:340] parse as old deprecated model file failed.

Any directions appreciated...

Asked by Michael1973 on 2020-01-26 13:56:35 UTC

Comments

Answers

You have two joints with the name j4.

Asked by nlamprian on 2020-02-02 12:11:50 UTC

Comments