How to add a color/material to a STL mesh in an URDF file?
I use STL meshes and urdf files and I can't seem to set the material colors in the urdf file. I tried adding material like this (similar to what I would do in an SDF file):
<gazebo reference="link_name">
<material>Gazebo/Red</material>
</gazebo>
or
<gazebo reference="link_name">
<material>
<script>
<uri>
file://media/materials/scripts/gazebo.material
</uri>
<name>
Gazebo/Red
</name>
</script>
</material>
</gazebo>
But it wouldn't work.
So: How can I set material/colours for STL files in an urdf file?
Asked by pDotGetName on 2016-06-23 04:52:50 UTC
Answers
You need to define the color separately such as in the file materials.xacro:
<material name="Orange">
<color rgba="${255/255} ${108/255} ${10/255} 1.0"/>
</material>
Import materials.xacro in your file:
<xacro:include filename="$(find your_robot_description)/urdf/materials.xacro" />
Then you can use the color specifying a material tag for each link, such as:
<link name="$link_name">
...
<visual>
...
<material name="Orange"/>
</visual>
...
</link>
For further information visit: http://gazebosim.org/tutorials/?tut=ros_urdf
Asked by mrslvgg on 2016-06-25 10:06:59 UTC
Comments
Well, that's basically how I do it. But the model doesn't change color even when I switch from Gazebo/White to Gazebo/Orange.
Asked by pDotGetName on 2016-06-27 03:16:01 UTC
I edited my answer. Check the new method.
Asked by mrslvgg on 2016-06-27 03:59:34 UTC
Isn't this edit's material for the ROS visualization? I currently have something like this:
In RVIZ the color is shown correctly, but in Gazebo it remains white. Could the STL file be somehow broken?
Asked by pDotGetName on 2016-06-27 06:36:21 UTC
This did not work for me, the model did not change colors.
Asked by JeremySMorgan on 2018-11-30 03:27:19 UTC
Previous answers are actually correct, the trick here is not to provide a name for the "visual". e.g.:
Do not:
<visual name="foo"> <!-- gazebo will ignore your color request -->
...
</visual>
Do instead:
<visual>
...
</visual>
Apart from that, you need to provide appropriate gazebo tags, I will leave a full working example below:
<?xml version="1.0"?>
<robot name="my_robot_name">
<!-- this color take effect only on rviz -->
<material name="WHITE_MTL">
<color rgba="0.0 1.0 0.0 1.0"/> <!-- rviz green color -->
</material>
<link name="my_link_name">
<inertial>
<origin xyz="0 0 1" rpy="0 0 0"/>
<mass value="0.5"/>
<inertia ixx="0.002" ixy="0" ixz="0" iyy="0.002" iyz="0" izz="0.002"/>
</inertial>
<visual> <!-- do not give a name! otherwise gazebo wont pick the color -->
<origin xyz="0 0.0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="package://my_robot_description/meshes/stl/my_file.stl" scale="1.0 1.0 1.0"/>
</geometry>
<material name="WHITE_MTL"/> <!-- rviz will use this color -->
</visual>
<collision name="my_collision1">
<origin xyz="0 1.0 0" rpy="0 0 0"/>
<geometry>
<cylinder radius="0.5" length="0.2"/>
</geometry>
</collision>
<collision name="my_collision2">
<origin xyz="0 -1.0 0" rpy="0 0 0"/>
<geometry>
<cylinder radius="0.1" length="0.3"/>
</geometry>
</collision>
</link>
<gazebo reference="my_link_name"> <!-- reference to a existing "link" -->
<!-- NOTE: use Gazebo/DepthMap to take color from mesh (.dae only) -->
<material>Gazebo/Orange</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<selfCollide>True</selfCollide>
</gazebo>
<!-- fix arm base, so that it does not fall -->
<link name="world"/>
<joint name="world_to_robot" type="fixed">
<parent link="world"/>
<child link="my_link_name"/>
<origin xyz="0 0 0.5" rpy="0 0 0"/>
</joint>
</robot>
Asked by Oscar Lima on 2021-03-23 13:39:17 UTC
Comments
Was this ever resolved?
Asked by plusk01 on 2017-01-05 01:14:26 UTC