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

Unable to load textures (UV mapped) on collada mesh in Gazebo (ROS electric)

asked 2013-10-08 22:05:07 -0500

Brijendra Singh gravatar image

Hi,

I'm trying to load collada models built through Ogre 1.7 in Gazebo (version 1.4.15, ROS electric). The meshes are those of simple cuboid boxes with different textures on each face (done through UV mapping in 3DS Max). The meshes are loading in Gazebo (meshes from Ogre 1.7) but the textures are not preserved on each face as per the mapping. Kindly suggest a solution for the same.

The collada (.dae) file, the UV mapped texture and the screen-shot of the box can be accessed from the following link:

https: //drive.google.com/ folderview?id=0B6bTMp3HA6dgOHZxQmQ2WmRzRk0&usp=sharing

P.S. Kindly remove the spaces from the link

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2020-05-01 12:20:26 -0500

updated 2020-05-01 21:25:14 -0500

jayess gravatar image

NOTE: using ROS melodic, ubuntu 18.04, 64 bits

For me it works with the following setup (assuming you already have the collada .dae file):

<link name="wheel_right_link">
<visual>
  <origin xyz="0 0 0" rpy="0 0 0"/>
  <geometry>
    <!--<cylinder length="0.018" radius="0.033"/>-->
    <mesh filename="package://my_ros_pkg/meshes/my_part/my_model.dae" scale="1 1 1"/>
  </geometry>
  <material name="dark"/>
</visual>

<collision>
  <origin xyz="0 0 0" rpy="0 0 0"/>
  <geometry>
    <cylinder length="0.018" radius="0.033"/>
  </geometry>
</collision>

<inertial>
  <origin xyz="0 0 0" />
  <mass value="2.8498940e-02" />
  <inertia ixx="1.1175580e-05" ixy="-4.2369783e-11" ixz="-5.9381719e-09"
           iyy="1.1192413e-05" iyz="-1.4400107e-11"
           izz="2.0712558e-05" />
  </inertial>
</link>

gazebo.xacro:

<gazebo reference="wheel_left_link">
<mu1>0.1</mu1>
<mu2>0.1</mu2>
<kp>50000.0</kp> <!-- default : 500000 -->
<kd>10.0</kd> <!-- default : 10.0 -->
<minDepth>0.001</minDepth>
<maxVel>0.1</maxVel>
<fdir1>1 0 0</fdir1>
<material>
    Gazebo/DepthMapVS
</material>
</gazebo>

The most important part is:

<material>
  Gazebo/DepthMapVS
</material>

To make the collada file (.dae) I use Blender and UV mapping (see uv mapping youtube tutorial) and before exporting the model in blender, go under material -> shading and turn on emit to about 0.65 . This will make the object more bright, otherwise it would look very dark.

If none of the above works for you, a full example (not with gazebo tags but with sdf) is available here.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2013-10-08 22:05:07 -0500

Seen: 1,011 times

Last updated: May 01 '20