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

Revision history [back]

Hi,

I dont know how you are attaching your depth cam to drone, but I assume you are doing it with URDF, in that URDF you should define parent link of camera_link correctly. If you do attach the depth cam to correct link on the drone , then tf tree should be complete, did you chechk that your tf tree is well connected ?

let us see what your tf tree looks like with;

rosrun tf view_frames

a pdf file will be created in the same directory that you executed above command

Hi,

I dont know how you are attaching your depth cam to drone, but I assume you are doing it with URDF, in that URDF you should define parent link of camera_link correctly. If you do attach the depth cam to correct link on the drone , then tf tree should be complete, did you chechk that your tf tree is well connected ?

let us see what your tf tree looks like with;

rosrun tf view_frames

a pdf file will be created in the same directory that you executed above command

Edit;

attaching sensors directly into world file of gazebo is not recommended. The sensors should be attached to body of file(URDF) of robot(drone in this case), and then the this URDF file should be spawned into gazebo.

for instance I can attach a depth camera to base_link of robot as follow;

<joint name="camera_joint" type="fixed">
    <parent link="base_link" />
    <child link="camera_link" />
    <origin rpy="0 1.57 0" xyz="0.6 -0.9 1.6" />
    <axis xyz="0 0 0" />
</joint>

<link name="camera_link">

</link>


    <gazebo reference="camera_link">
          <sensor name="camera" type="depth">
            <pose>0.0085 0.0105 0.0197 0 0 0</pose>
            <update_rate>30</update_rate>
            <camera>
              <horizontal_fov>1.01229</horizontal_fov>
              <image>
                <width>1024</width>
                <height>1024</height>
                <format>R8G8B8</format>
              </image>
              <clip>
                <near>0.2</near>
                <far>1.5</far>
              </clip>
            </camera>
            <plugin name="camera_plugin" filename="libgazebo_ros_openni_kinect.so">
              <baseline>0.2</baseline>
              <alwaysOn>true</alwaysOn>
              <!-- Keep this zero, update_rate in the parent <sensor> tag
                will control the frame rate. -->
              <updateRate>0.0</updateRate>
              <cameraName>camera_ir</cameraName>
              <imageTopicName>/camera/color/image_raw</imageTopicName>
              <cameraInfoTopicName>/camera/color/camera_info</cameraInfoTopicName>
              <depthImageTopicName>/camera/depth/image_raw</depthImageTopicName>
              <depthImageCameraInfoTopicName>/camera/depth/camera_info</depthImageCameraInfoTopicName>
              <pointCloudTopicName>/camera/depth/points</pointCloudTopicName>
              <frameName>camera_link</frameName>
              <pointCloudCutoff>0.2</pointCloudCutoff>
              <pointCloudCutoffMax>1.5</pointCloudCutoffMax>
              <distortionK1>0</distortionK1>
              <distortionK2>0</distortionK2>
              <distortionK3>0</distortionK3>
              <distortionT1>0</distortionT1>
              <distortionT2>0</distortionT2>
              <CxPrime>0</CxPrime>
              <Cx>0</Cx>
              <Cy>0</Cy>
              <focalLength>0</focalLength>
              <hackBaseline>0</hackBaseline>
            </plugin>
          </sensor>
    </gazebo>