What is wrong with my xacro file that I can't see the color of the box in gazebo?
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?
Asked by rahul on 2016-06-24 15:31:13 UTC
Answers
Hi,
You'll have to define the gazebo color as well
<gazebo reference="base_link">
<material>Gazebo/Yellow</material>
</gazebo>
See http://gazebosim.org/tutorials/?tut=ros_urdf
Cheers
Asked by ffurrer on 2016-06-24 23:26:51 UTC
Comments