Using projectors in Gazebo 1.9 + ROS Hydro?
I was trying to create an example projector project to demonstrate some problems I was having with projector poses, but couldn't get the texture to appear at all, there is just what appears a default error image with yellow diagonal bars on black.
example image on github, (don't have karma to upload and providing a link isn't working)
This is the xacro file responsible:
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="projector_test">
<link name="world"/>
<link name="link_projector">
<visual>
<geometry>
<cylinder length="0.2" radius="0.05" />
</geometry>
</visual>
<inertial>
<mass value="1.0"/>
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
</inertial>
</link>
<joint name="joint_projector" type="fixed">
<origin xyz="0 0 2.0" rpy="0.0 0 0" />
<parent link="world" />
<child link="link_projector" />
</joint>
<gazebo reference="link_projector">
<projector name="projector_test1">
<pose>0 0 0 0 0 0</pose>
<!-- this isn't getting loaded properly -->
<texture>$(find projector_test)/urdf/test_pattern.png</texture>
<!--texture>test_pattern.png</texture-->
<fov>0.6</fov>
<near_clip>0.1</near_clip>
<far_clip>10.0</far_clip>
</projector>
</gazebo>
</robot>
This is from projector test, there is also a launch file there and catkin package.xml and CMake files, roslaunch projector_test projector_test.launc
h launches it.
In another project I was able to make projectors work somewhat, I had the png in a meshes dir and I think that because another resource was loaded from the same directory (and which had a full path) the png was able to be found.
Could you solve this problem? I'm facing the same problem and this happens even with the full path of the image. I'm using Gazebo version 7.14.0 + ROS Kinetic. Edit: I could not find the answer yet, but experimenting other codes I've found out that replacing the texture tag by the following one actually replaces the yellow diagonal bars error image: <texture>stereo_projection_pattern_high_res_red.png</texture> Also, some images from /usr/share/gazebo-7/media/materials/textures work, others not