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

Revision history [back]

click to hide/show revision 1
initial version

1) If you don't see any camera stream from gazebo, it probably does not know the camera exists.

Does your xacro file define the gazebo sensor somewhere, as described in this tutorial? The macro you are using might not contain this part.

If that is the case, one way to fix it is to include another file in your main URDF file, with content like this:

<?xml version="1.0"?>
<robot>
  <gazebo reference="your_camera_link">
    <sensor type="depth" name="your_camera">       
      <always_on>true</always_on>
      <visualize>true</visualize>             
      <camera>
          <horizontal_fov>1.047</horizontal_fov>
          <image>
              <width>640</width>
              <height>480</height>
              <format>R8G8B8</format>
          </image>
          <depth_camera>

          </depth_camera>
          <clip>
              <near>0.1</near>
              <far>100</far>
          </clip>
      </camera>
      <plugin name="camera_controller" filename="libgazebo_ros_openni_kinect.so">
          <baseline>0.2</baseline>
          <alwaysOn>true</alwaysOn>
              <updateRate>10.0</updateRate>
              <cameraName>your_camera</cameraName>
              <frameName>your_camera_link</frameName>                   
          <imageTopicName>rgb/image_raw</imageTopicName>
          <depthImageTopicName>depth/image_raw</depthImageTopicName>
          <pointCloudTopicName>depth/points</pointCloudTopicName>
          <cameraInfoTopicName>rgb/camera_info</cameraInfoTopicName>              
          <depthImageCameraInfoTopicName>depth/camera_info</depthImageCameraInfoTopicName>            
          <pointCloudCutoff>0.4</pointCloudCutoff>                
              <hackBaseline>0.07</hackBaseline>
              <distortionK1>0.0</distortionK1>
              <distortionK2>0.0</distortionK2>
              <distortionK3>0.0</distortionK3>
              <distortionT1>0.0</distortionT1>
              <distortionT2>0.0</distortionT2>
          <CxPrime>0.0</CxPrime>
          <Cx>0.0</Cx>
          <Cy>0.0</Cy>
          <focalLength>0.0</focalLength>
          </plugin>
    </sensor>
  </gazebo>
</robot>

2) You should not change the robot macro file directly, since that is supplied by the robot manufacturer. If you want to attach a camera to the robot, just add the link+joint outside of the macro.