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

Gazebo: Invalid <param> tag: Cannot load command parameter [robot_description]:

asked 2016-11-10 13:41:18 -0500

nikku gravatar image

updated 2016-11-10 14:22:17 -0500

Hi.

I'm using Ubuntu 14.04 ROS Indigo Gazebo2

I am quite new to ROS and Gazebo and I'm following this Tutorial link:here.

I did everything like in the tutorial, nut when I want to use roslaunch to launch my launchfile I get the following error:

 Invalid <param> tag: Cannot load command parameter [robot_description]: command [/opt/ros/indigo/share/xacro/xacro.py 
 /home/myuser/catkin_ws/src/mybot_description/urdf/mybot.xacro] returned with code [1]. 

 Param xml is <param command="$(find xacro)/xacro.py $(find mybot_description)/urdf/mybot.xacro"   name="robot_description"/>
 The traceback for the exception was written to the log file

When I enter

rosrun xacro xacro.py /home/myuser/catkin_ws/src/mybot_description/urdf/mybot.xacro

I get

Traceback (most recent call last):
  File "/opt/ros/indigo/share/xacro/xacro.py", line 62, in <module>
    xacro.main()
  File "/opt/ros/indigo/lib/python2.7/dist-packages/xacro/__init__.py", line 687, in main
    process_includes(doc, os.path.dirname(args[0]))
  File "/opt/ros/indigo/lib/python2.7/dist-packages/xacro/__init__.py", line 269, in process_includes
    % (filename, str(e)))
xacro.XacroException: included file "/home/myuser/catkin_ws/src/mybot_description/urdf/macros.xacro" generated an error during XML parsing: unbound prefix: line 2, column 0

My macro file looks like this

<xacro:macro name="box_inertia" params="m x y z">
  <inertia  ixx="${m*(y*y+z*z)/12}" ixy = "0" ixz = "0"
    iyy="${m*(x*x+z*z)/12}" iyz = "0"
    izz="${m*(x*x+z*z)/12}"
  />
 </xacro:macro>

And my mybot.xacro looks like this:

<?xml version="1.0"?>

<robot name="mybot" xmlns:xacro="http://www.ros.org/wiki/xacro">
    <!-- Put here the robot description -->

<xacro:property name="PI" value="3.1415926535897931"/>

<xacro:property name="chassisHeight" value="0.1"/>
<xacro:property name="chassisLength" value="0.4"/>
<xacro:property name="chassisWidth" value="0.2"/>
<xacro:property name="chassisMass" value="50"/>

<xacro:property name="casterRadius" value="0.05"/>
<xacro:property name="casterMass" value="5"/>

<xacro:property name="wheelWidth" value="0.05"/>
<xacro:property name="wheelRadius" value="0.1"/>
<xacro:property name="wheelPos" value="0.2"/>
<xacro:property name="wheelMass" value="5"/>

<xacro:property name="cameraSize" value="0.05"/>
<xacro:property name="cameraMass" value="0.1"/>                             


 <xacro:include filename="$(find mybot_description)/urdf/mybot.gazebo" />
 <xacro:include filename="$(find mybot_description)/urdf/materials.xacro" />
 <xacro:include filename="$(find mybot_description)/urdf/macros.xacro" />


    <link name="footprint" />

<joint name="base_joint" type="fixed">
  <parent link="footprint"/>
  <child link="chassis"/>
</joint>



    <link name='chassis'>
  <collision> 
    <origin xyz="0 0 ${wheelRadius}" rpy="0 0 0"/> 
    <geometry> 
      <box size="${chassisLength} ${chassisWidth} ${chassisHeight}"/> 
    </geometry> 
  </collision>
  <visual> 
    <origin xyz="0 0 ${wheelRadius}" rpy="0 0 0"/> 
    <geometry> 
      <box size="${chassisLength} ${chassisWidth} ${chassisHeight}"/> 
    </geometry> 
    <material name="orange"/>
  </visual>
  <inertial> 
    <origin xyz="0 0 ${wheelRadius}" rpy="0 0 0"/> 
    <mass value="${chassisMass}"/> 
    <box_inertia m="${chassisMass}" x="${chassisLength}" y="${chassisWidth}" z="${chassisHeight}"/>
  </inertial>
</link>



</robot>

Thanks for your help!

edit retag flag offensive close merge delete

Comments

It looks like there is something wrong with your macros.xacro file. Can you edit your question and add the relevant xacro files (at least macros.xacro and mybot.xacro)?

jarvisschultz gravatar image jarvisschultz  ( 2016-11-10 13:58:30 -0500 )edit

I edited my comment

nikku gravatar image nikku  ( 2016-11-10 14:02:17 -0500 )edit
1

Cool... in the future, please use the code button (the 101010 button) to put snippets in code blocks

jarvisschultz gravatar image jarvisschultz  ( 2016-11-10 14:20:58 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
2

answered 2016-11-10 14:36:44 -0500

I believe the issue is that your macros.xacro file doesn't have a <robot> tag as the root element. So something like

<robot name="mybot_macros" xmlns:xacro="http://www.ros.org/wiki/xacro">
  <xacro:macro name="box_inertia" params="m x y z">
    <inertia  ixx="${m*(y*y+z*z)/12}" ixy="0" ixz="0"
              iyy="${m*(x*x+z*z)/12}" iyz="0"
              izz="${m*(x*x+z*z)/12}"/>
  </xacro:macro>
</robot>

should fix the issue.

edit flag offensive delete link more

Comments

Thanks a lot. Fixed it and I cant launch my world now. :D :D

nikku gravatar image nikku  ( 2016-11-10 14:41:27 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2016-11-10 13:41:18 -0500

Seen: 6,067 times

Last updated: Nov 10 '16