ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Why will my URDF model not load into Gazebo?

asked 2020-09-29 14:14:02 -0500

ARMWilkinson gravatar image

I have developed a simple robot model using a urdf file and several meshes and I am able to load it up in RViz without issue. However, whenever I try to load it into Gazebo it will not appear. I have tried using several methods such as roslaunch and inserting the model into Gazebo itself.

Here is the urdf file:

<?xml version="1.0"?>
<robot name="Bilkins">


  <link name="chassis">
    <visual>
      <geometry>
        <mesh filename="package://bilkins/meshes/chassis.dae" scale="0.1 0.1 0.1" />
      </geometry>
      <origin rpy="0.0 0 0" xyz="0 0 0"/>
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://bilkins/meshes/chassis.dae" scale="0.1 0.1 0.1" />
      </geometry>
      <origin rpy="0.0 0 0" xyz="0 0 0"/>
    </collision>
    <inertial>
      <mass value="0.2" />
      <inertia ixx="0.4" ixy="0.0" ixz="0.0" iyy="0.4" iyz="0.0" izz="0.2"/>
    </inertial>
  </link>

  <link name="rear_axle">
    <visual>
      <geometry>
        <mesh filename="package://bilkins/meshes/rear_axle.dae" scale="0.1 0.1 0.1" />
      </geometry>
      <origin xyz="-1.3 0 -0.5" />
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://bilkins/meshes/rear_axle.dae" scale="0.1 0.1 0.1" />
      </geometry>
      <origin xyz="-1.3 0 -0.5" />
    </collision>
    <inertial>
      <mass value="0.14" />
      <inertia ixx="0.4" ixy="0.0" ixz="0.0" iyy="0.4" iyz="0.0" izz="0.2"/>
    </inertial>
  </link>

  <link name="front_axle">
    <visual>
      <geometry>
        <mesh filename="package://bilkins/meshes/front_axle.dae" scale="0.1 0.1 0.1" />
      </geometry>
      <origin xyz="1.3 0 -0.5" />
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://bilkins/meshes/front_axle.dae" scale="0.1 0.1 0.1" />
      </geometry>
      <origin xyz="1.3 0 -0.5" />
    </collision>
    <inertial>
      <mass value="0.1" />
      <inertia ixx="0.4" ixy="0.0" ixz="0.0" iyy="0.4" iyz="0.0" izz="0.2"/>
    </inertial>
  </link>

  <link name="front_left_wheel">
    <visual>
      <geometry>
        <mesh filename="package://bilkins/meshes/front_left_wheel.dae" scale="0.1 0.1 0.1" />
      </geometry>
      <origin xyz="1.3 0.9 -0.5" />
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://bilkins/meshes/front_left_wheel.dae" scale="0.1 0.1 0.1" />
      </geometry>
      <origin xyz="1.3 0.9 -0.5" />
    </collision>
    <inertial>
      <mass value="0.02" />
      <inertia ixx="0.4" ixy="0.0" ixz="0.0" iyy="0.4" iyz="0.0" izz="0.2"/>
    </inertial>
  </link>

  <link name="front_right_wheel">
    <visual>
      <geometry>
        <mesh filename="package://bilkins/meshes/front_right_wheel.dae" scale="0.1 0.1 0.1" />
      </geometry>
      <origin xyz="1.3 -0.9 -0.5" />
    </visual>
    <collision>
      <geometry>
        <mesh filename="package://bilkins/meshes/front_right_wheel.dae" scale="0.1 0.1 0.1" />
      </geometry>
      <origin ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2020-09-30 04:29:15 -0500

Weasfas gravatar image

updated 2020-10-01 05:06:27 -0500

Hi @ARMWilkinson,

First of all, you do not need a Gazebo model just a URDF or, preferably a Xacro description. Having said that what you are doing in only loading the robot_description in the parameter server, that is the reason why only Rviz is able to see it since Rviz is reading that description from that parameter.

To be able to generate the model in Gazebo you need to call a special python script named "spawner" that it is in change of generating a model in the Gazebo simulation and with the robot_description you load. I recommend you to check this tutorial to learn more about this.

To put things clear, imagine you have your robot_description and want to simulate it in Gazebo, Ideally you will have something like:

<launch>

  <arg name="model" default="$(find bilkins)/urdf/bilkins.urdf"/>
  <arg name="gui" default="true" />
  <arg name="rvizconfig" default="$(find bilkins)/rviz/urdf.rviz" />
  <arg name="output" default="log"/>

  <!-- Coordinates to spawn model -->
  <arg name="x" default="0.0"/>
  <arg name="y" default="0.0"/>
  <arg name="z" default="0.01"/>
  <arg name="roll" default="0.0"/>
  <arg name="pitch" default="0.0"/>
  <arg name="yaw" default="0.0"/>

  <!-- Load model in parameter server -->
  <param name="robot_description" command="$(find xacro)/xacro $(arg model)" />

  <!-- Generate joint_states and tf_tree -->
  <node if="$(arg gui)" name="joint_state_publisher" pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" />
  <node unless="$(arg gui)" name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
  <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
  <node name="rviz" pkg="rviz" type="rviz" args="-d $(arg rvizconfig)" required="true" />

  <!-- Run a python script to the send a service call to gazebo_ros to spawn a URDF robot -->
  <node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="$(arg output)"
    args="-urdf -model bilkins_robot -param robot_description -x $(arg x) -y $(arg y) -z $(arg z) -R $(arg roll) -P $(arg pitch) -Y $(arg yaw)"/>

</launch>

So, in order, what you have is: Load URDF in parameter server -> Generate robots TF_tree and joint_states -> Spawn model in Gazebo.

Hope this helps you.

Regards.

edit flag offensive delete link more

Comments

Thanks, I have tried implementing this but I when I use roslaunch I get an error stating:

RLException: [/home/andrew/catkin_ws/src/bilkinsrobot/launch/gazebo.launch] requires the 'output' arg to be set The traceback for the exception was written to the log file

ARMWilkinson gravatar image ARMWilkinson  ( 2020-09-30 08:35:47 -0500 )edit

Ops, I forgot to include that argument. That is on me, sorry. I updated my original answer.

Weasfas gravatar image Weasfas  ( 2020-10-01 05:06:10 -0500 )edit

No worries, I really appreciate the help. The error's no longer appearing now, however, whenever I use roslaunch it opens the model up in RViz.

ARMWilkinson gravatar image ARMWilkinson  ( 2020-10-01 07:44:18 -0500 )edit

Actually scratch that, I've managed to get it loading into Gazebo now. Thank you so much for your help.

ARMWilkinson gravatar image ARMWilkinson  ( 2020-10-01 08:02:26 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2020-09-29 14:14:02 -0500

Seen: 1,671 times

Last updated: Oct 01 '20