Sensor output to ignition topic not working for depth_camera and gpu_ray
Hi, I'm trying to simulate a realsense type model using the built-in gazebo sensors and to output on ignition topics. In the model below, I have a number of camera frames, but I find that only rgb camera topics are produced. Depth Topics are not available and no point clouds are produced by gpu_ray.
Additionlly, gazebo complains of
[Wrn] [msgs.cc:1841] Conversion of sensor type[gpu_ray] not supported.
[Wrn] [msgs.cc:1841] Conversion of sensor type[depth_camera] not supported.
and
ign topic -l
only shows the following topics:
/default/d435slam/base_link/camera_left_ir_frame_camera/image
/default/d435slam/base_link/camera_link_camera/image
/default/d435slam/base_link/camera_right_ir_frame_camera/image
/introspection/jxwlfx/items_update
I am using Gazebo 11 and sdf 1.7.
This is my sdf file:
<sdf version='1.7'>
<model name='d435slam'>
<link name='base_link'>
<inertial>
<pose>0 0 0 0 -0 0</pose>
<mass>0.564</mass>
<inertia>
<ixx>0.00388124</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.00049894</iyy>
<iyz>0</iyz>
<izz>0.00387926</izz>
</inertia>
</inertial>
<collision name='base_link_fixed_joint_lump__camera_link_collision'>
<pose>0 0 0.0125 0 -0 0</pose>
<geometry>
<box>
<size>0.02505 0.09 0.025</size>
</box>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='base_link_fixed_joint_lump__camera_link_visual'>
<pose>0.0149 0 0.0125 1.5708 -0 1.5708</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://d435slam/meshes/d435.dae</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/Black</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual>
<velocity_decay/>
<velocity_decay/>
<sensor name='camera_link_camera' type='camera'>
<always_on>1</always_on>
<update_rate>30</update_rate>
<topic>rgb_cam</topic>
<camera>
<horizontal_fov>1</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
</image>
<clip>
<near>0.1</near>
<far>700</far>
</clip>
</camera>
<pose>0 0 0 0 -0 0</pose>
</sensor>
<velocity_decay/>
<sensor name='depth_point_cloud' type='gpu_ray'>
<always_on>1</always_on>
<update_rate>30</update_rate>
<topic>points</topic>
<ray>
<scan>
<horizontal>
<samples>48</samples>
<resolution>1</resolution>
<min_angle>-0.6</min_angle>
<max_angle>0.6</max_angle>
</horizontal>
<vertical>
<samples>36</samples>
<resolution>1</resolution>
<min_angle>-0.5</min_angle>
<max_angle>0.5</max_angle>
</vertical>
</scan>
<range>
<min>0.2</min>
<max>40</max>
<resolution>1</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<pose>0.0149 0.0175 0.0125 0 -0 0</pose>
</sensor>
<velocity_decay/>
<sensor name='camera_left_ir_frame_camera' type='camera'>
<always_on>1</always_on>
<update_rate>30</update_rate>
<topic>ir_left</topic>
<camera>
<horizontal_fov>1</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
</image>
<clip>
<near>0.1</near>
<far>700</far>
</clip>
</camera>
<pose>0.0149 0.0175 0.0125 0 -0 0</pose>
</sensor>
<velocity_decay/>
<sensor name='depth_camera' type='depth_camera'>
<always_on>1</always_on>
<update_rate>30</update_rate>
<topic>depth_camera</topic>
<camera>
<horizontal_fov>1</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
</image>
<depth_camera>
<clip>
<near>0.1</near>
<far>50</far>
</clip>
<output>depths</output>
</depth_camera>
</camera>
<pose>0.0149 0.0175 0.0125 0 -0 0</pose>
</sensor>
<gravity>1</gravity>
<velocity_decay/>
<sensor name='camera_right_ir_frame_camera' type='camera'>
<always_on>1</always_on>
<update_rate>30</update_rate>
<topic>ir_right</topic>
<camera>
<horizontal_fov>1</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
</image>
<clip>
<near>0.1</near>
<far>700</far>
</clip>
</camera>
<pose>0.0149 -0.0325 0.0125 0 -0 0</pose>
</sensor>
</link>
</model>
</sdf>
Asked by PMilani on 2020-05-17 07:58:45 UTC
Comments