Can't point depth camera in forward direction
I defined custom robot with Asus Xtyion camera, but I have one problem with depth camera orientation. There are two other questions with the similar problem, but they are about Rviz part of my problem, where I also have Gazebo part of the problem :) I use libgazebo_ros_camera and libgazebo_ros_openni_kinect controllers. RGB image is displayed properly in RViz, but depth cloud has two problems. One is that gazebo for some reason points depth camera to the left side of the robot/camera, and changing pose tag is not changing anything. At first that was the problem with RGB camera too, but pose tag helped in that case. Second problem is that in Rviz point cloud is rotated around Y axis I think, so it is in front of the robot, but points down through the ground, and displays the scene from the left side of the robot. Any suggestions? Here is the part of URDF:
<gazebo reference="Camera">
<sensor type="camera" name="xtion_rgb">
<update_rate>30.0</update_rate>
<camera name="xtion_rgb">
<pose>0 0 0 3.14 0 1.57</pose>
<horizontal_fov>1.01229</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.05</near>
<far>50</far>
</clip>
<noise>
<type>gaussian</type>
<!-- Noise is sampled independently per pixel on each frame.
That pixel's noise value is added to each of its color
channels, which at that point lie in the range [0,1]. -->
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<plugin name="RGB_camera_controller" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
<cameraName>xtion_rgb</cameraName>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>Camera</frameName>
<hackBaseline>0.07</hackBaseline>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
</plugin>
</sensor>
<sensor type="depth" name="xtion_d">
<update_rate>30.0</update_rate>
<camera name="xtion_ir">
<!--<pose>0 0 0 0 0 0</pose>-->
<horizontal_fov>1.01229</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.05</near>
<far>10</far>
</clip>
</camera>
<plugin name="Depth_camera_controller" filename="libgazebo_ros_openni_kinect.so">
<baseline>0.2</baseline>
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate> <!-- Not sure why 6 -->
<cameraName>xtion_ir</cameraName>
<imageTopicName>depth/image_raw</imageTopicName>
<cameraInfoTopicName>depth/camera_info</cameraInfoTopicName>
<depthImageTopicName>depth/image_raw</depthImageTopicName>
<depthImageInfoTopicName>depth/camera_info</depthImageInfoTopicName>
<pointCloudTopicName>depth/points</pointCloudTopicName>
<frameName>Camera</frameName>
<pointCloudCutoff>0.05</pointCloudCutoff>
<pointCloudCutoffMax>10</pointCloudCutoffMax>
<rangeMax>10.0</rangeMax>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
<CxPrime>0</CxPrime>
<Cx>0</Cx>
<Cy>0</Cy>
<focalLength>0</focalLength>
<hackBaseline>0</hackBaseline>
</plugin>
</sensor>
</gazebo>
it has nothing to do with your robot description, it is the launch file you need to look at