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

What is wrong with my xacro file that I can't see the color of the box in gazebo?

asked 2016-06-24 15:42:10 -0500

cybodroid gravatar image

Here is my xacro file:

<?xml version="1.0" ?>

<robot name="$(arg roboname)" xmlns:xacro="http://www.ros.org/wiki/xacro">

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

<link name="base_link">
     <collision>
         <origin xyz="0 0 1" rpy="0 0 ${-PI/2}"/>
           <geometry>
            <box size="2.62 1.3 1.4478"/>
        </geometry>
      </collision>
    <gravity>0</gravity>
     <visual>
        <origin xyz="0 0 1" rpy="0 0 ${-PI/2}"/>
        <geometry>
            <box size="2.62 1.3 1.4478"/>
        </geometry>
         <material name="Yellow"/>
     </visual>

</link>

<joint name="inertial_joint" type="fixed">
      <parent link="base_link"/>
      <child link="main_mass"/>
      <origin xyz="0 0 0" rpy="0 0 0"/>
</joint>

<link name="main_mass" type="fixed">
    <!-- <parent link="inertial_joint"/> -->
     <gravity>0</gravity>
     <inertial>
        <origin xyz="0 0 1.0639" rpy="0 0 0"/>
        <mass value="1"/>
        <inertia
          ixx="1"  ixy="0.000000" ixz="0"
          iyy="0" iyz="0.000000"
          izz="0"/>
      </inertial>
</link>

</robot>

I want box to be of yellow color but I can't see in Yellow color in gazebo. How should I fix it?

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
2

answered 2016-06-24 18:10:08 -0500

updated 2016-06-24 18:14:14 -0500

Assuming you are at least on ROS Indigo with Gazebo 2.x.

The colors in ROS URDF and Gazebo SDF are not of the same flavour. Citing from URDF in Gazebo tutorial:

A standard URDF can specify colors using a tag such as in the RRBot:

<material name="orange"/>

With the color orange defined separately such as in the file materials.xacro:

<material name="orange">
  <color rgba="${255/255} ${108/255} ${10/255} 1.0"/>
</material>

Unfortunately, this method of specifying link colors does not work in Gazebo as it adopts OGRE's material scripts for coloring and texturing links. Instead, a Gazebo material tag must be specified for each link, such as:

<gazebo reference="link1">
  <material>Gazebo/Orange</material>
</gazebo>

These <gazebo reference=...> tags allow to embed native SDF commands for model links into URDF.

So, you should include in your URDF something like:

<gazebo reference="base_link">
  <material>Gazebo/Yellow</material>
</gazebo>

It is a good idea to keep color statements both for URDF and SDF if you are going to visualize the model both in RViz and Gazebo.

If you are only interested in Gazebo without ROS integration, then you may prefer to use SDF to describe your robot.

Please refer to the tutorial.

edit flag offensive delete link more

Comments

Thanks for your explanation. It worked.

cybodroid gravatar image cybodroid  ( 2016-06-27 13:39:43 -0500 )edit
0

answered 2021-08-11 10:08:24 -0500

Manar gravatar image

Hi, I am just posting so that other users could see. I managed to add a color on Gazebo based on this tutorial: http://gazebosim.org/tutorials/?tut=r... I used this in my xacro file :

   <gazebo reference="link1">
    <material>Gazebo/Orange</material>
   </gazebo>

This uses already built-in gazebo colors from gazebo.materialswhich you can find this link: https://github.com/osrf/gazebo/blob/m...

I wanted to add a red sphere but there was no pure red color in the built-in ones. The present colors had either dark or light gradients. To solve this I added a custom color to the gazebo.materials I found it on my computer on this path:(I am runing Ubuntu 20.04) /usr/share/gazebo-11/media/materials/scripts/gazebo.material

To insert pure red, i added this code:

material Gazebo/RED
      {
        technique
        {
          pass
          {
            texture_unit
            {
              colour_op_ex source1 src_manual src_current 1 0 0
            }
          } 
        }
      }

Then you have to save as sudo. I used visual studio to do that. It is possible that with other code editor it does't allow you save.

You can find more details on adding a color in here: https://wiki.ogre3d.org/Materials#Sol...

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2016-06-24 15:42:10 -0500

Seen: 6,793 times

Last updated: Aug 11 '21