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

xacro macros model not showing up in rviz(noetic)

asked 2021-06-09 05:19:49 -0600

siddharthcb gravatar image

updated 2021-06-09 05:21:18 -0600

hi, I am trying to visualize xacro macros model on rviz which works fine in gazebo but i have few issues while visualizing it in rviz. in gazebo i am able to visualize the links, collision and inertia are properly configured but when i launch rviz i get this warning

    Unable to parse component [${base_length}] to a double (while parsing a vector value)
    [ERROR] [1623216223.772835121, 69.582000000]: Could not parse visual element for Link [base_link]

i tried rosparam load <myxacro.urdf.xacro> robot_description and the same error. i followed the solution in this thread but no luck.

and i also get robotmodel error.

    Parameter [robot_description] does not exist, and was not found by searchParam()

i tried running export LC_NUMERIC="en_US.UTF-8" before rviz but does not solve it.

my xacro files

inertials.xacro

<?xml version="1.0" ?>
<!--  xacro macros for inertials.

    Define xacro macros for math constants and inertials:

    - solid cuboid
    - solid cylinder
    - null (a placeholder inertial for logical link elements)
 -->
<robot name="inertials" xmlns:xacro="http://wiki.ros.org/xacro">

    <!-- Math constants -->
    <xacro:property name="math_pi"        value="3.141592653589793" />
    <xacro:property name="math_pi_over_2" value="1.5707963267948966" />
    <xacro:property name="math_pi_over_4" value="0.785398163397448" />

    <!-- Inertial for solid cuboid with dimensions x y z  -->
    <xacro:macro name="solid_cuboid_inertial" params="rpy xyz mass x y z">
        <inertial>
            <origin rpy="${rpy}" xyz="${xyz}"/>
            <mass value="${mass}" />
            <inertia
                ixx="${mass * (y * y + z * z) / 12.0}" ixy="0.0" ixz="0.0"
                iyy="${mass * (x * x + z * z) / 12.0}" iyz="0.0"
                izz="${mass * (x * x + y * y) / 12.0}" />
        </inertial>
    </xacro:macro>
    <solid_cuboid_inertial/>

    <!-- Inertial for solid cylinder with radius and length aligned to z-axis  -->
    <xacro:macro name="solid_cylinder_inertial" params="rpy xyz mass radius length">
        <inertial>
            <origin rpy="${rpy}" xyz="${xyz}"/>
            <mass value="${mass}" />
            <inertia
                ixx="${mass * (3.0 * radius * radius + length * length) / 12.0}" ixy="0.0" ixz="0.0"
                iyy="${mass * (3.0 * radius * radius + length * length) / 12.0}" iyz="0.0"
                izz="${mass * (radius * radius) / 2.0}" />
        </inertial>
    </xacro:macro>
    <solid_cylinder_inertial/>

    <!-- A null inertial - used in placeholder links to esure the model will work in Gazebo -->
    <xacro:macro name="null_inertial">
        <inertial>
            <mass value="0.001"/>
            <inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
        </inertial>
    </xacro:macro>
    <null_inertial/>

</robot>

materials.xacro

<?xml version="1.0" ?>
<!--  xacro macros for robot materials.
 -->
<robot name="materials" xmlns:xacro="http://wiki.ros.org/xacro">
   <material name="red">
        <color rgba="0.8 0 0 1"/>
    </material>

    <material name="green">
        <color rgba="0 0.8 0 1"/>
    </material>

    <material name="blue">
        <color rgba="0 0 0.8 1"/>
    </material>

    <material name="orange">
        <color rgba="0.8 0.25 0 1"/>
    </material>

wheel.xacro

< ...
(more)
edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
2

answered 2021-06-09 08:31:22 -0600

djchopp gravatar image

updated 2021-06-09 08:53:42 -0600

EDIT: After playing a bit with the git repo, I am pretty sure you just need to change the Robot Description topic source in rviz. Solution to this is bolded in answer below.

A couple of quick things I noticed:

You should not have inertial components on your base link. Instead make a dummy base link and a static joint. Replace your base_link definition with this:

<!-- Required Base Link -->
<link name="base_link"/>

<!-- Body link -->
<link name="body_link">
  <visual>
    <origin xyz="0 0 0" rpy="0 0 0"/>
    <geometry>
      <box size="${base_length} ${base_width} ${base_height}"/>
    </geometry>
    <material name="green" />
  </visual>
  <collision>
    <origin xyz="0 0 0" rpy="0 0 0"/>
    <geometry>
      <box size="${base_length} ${base_width} ${base_height}"/>
    </geometry>
  </collision>
  <xacro:solid_cuboid_inertial 
      rpy="0 0 0" xyz="0 0 0"
      mass="${base_mass}"
      x="${base_length}" y="${base_width}" z="${base_height}" />
</link>

<!-- A joint to connect the body to the base_link -->
<joint name="body_joint" type="fixed">
  <origin xyz="0 0 0" rpy="0 0 0" />
  <parent link="base_link"/>
  <child link="body_link"/>
</joint>

You won't be able to pass just the xacro to rosparam using rosparam load <myxacro.urdf.xacro> robot_description because a xacro file is not a valid robot description. It needs to be processed into a urdf (which is what your launchfile is doing with <param name="robot_description" command="$(find xacro)/xacro --inorder $(arg model)"/>

Speaking of that command, you can remove the --inorder flag as that has been the default for a couple distributions now.

Your materials.xacro is missing an end tag for </robot> (at least in this posting, maybe not in your actual code)

In RVIZ, your robot description topic is no longer just robot_description because you are grouping into a namespace in your launchfile. Try replacing that with the full param path /bicycle_bot/robot_description

If you are still running into errors, please run a rosrun xacro xacro path/to/bicycle_bot.urdf.xacro and make sure the robot description is generated without errors (it will print the resulting urdf to screen).

Hope this helps!

edit flag offensive delete link more

Comments

thanks @djchopp. it worked. i did not have to add an extra dummy link though.

siddharthcb gravatar image siddharthcb  ( 2021-06-10 00:12:58 -0600 )edit
1

answered 2021-06-09 09:05:27 -0600

Ranjit Kathiriya gravatar image

Hello @siddharthcb,

I have checked everything myself which was related to your post.

  1. Urdf is perfect just it is having a minor warning - Don't try to fix that. It's okay your code will run perfectly.
  2. In your Rviz -> general option -> fixed frame -> make it to odom. It was a throwing an error because you have not installed drivers for it.

Here is a link for the drivers: https://github.com/ranjitkathiriya/st...

Note: that you are installing the noetic-devel branch of this driver. If you are installing any other branch it will through an error.

If you have any issues. Please! feel free to drop comments.

edit flag offensive delete link more

Comments

thanks ranjit. for my application, drivers werent needed it was a minor robot_description error as djchopp pointed.

siddharthcb gravatar image siddharthcb  ( 2021-06-10 00:12:22 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2021-06-09 05:19:49 -0600

Seen: 1,443 times

Last updated: Jun 09 '21