1 | initial version |
Thank you for your answers.
I was rather looking for how to define a stereo camera (not how to visualize it), but the answer was interesting.
The old way of adding stereo cameras in Gazebo classic was to:
- attach a sensor to the camera_link
- set the sensor type to multicamera
- define two cameras in this sensor using the << camera >> tag
- add a plugin to the sensor
- explicitly set the baseline in the plugin using the << hack_baseline >> tag
Here is an example of stereo camera for Gazebo classic:
<gazebo reference="camera_link">
<sensor type="multicamera" name="stereo_camera">
<update_rate>10.0</update_rate>
<always_on>true</always_on>
<camera name="left">
<pose>0 0 0 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>1024</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.0</stddev>
</noise>
<distortion>
<k1>0.0</k1>
<k2>0.0</k2>
<k3>0.0</k3>
<p1>0.0</p1>
<p2>0.0</p2>
<center>0.5 0.5</center>
</distortion>
</camera>
<camera name="right">
<pose>0 -0.12 0 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>1024</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.0</stddev>
</noise>
<distortion>
<k1>0.0</k1>
<k2>0.0</k2>
<k3>0.0</k3>
<p1>0.0</p1>
<p2>0.0</p2>
<center>0.5 0.5</center>
</distortion>
</camera>
<plugin name="stereo_camera_controller" filename="libgazebo_ros_camera.so">
<ros>
<namespace></namespace>
<argument>image_raw:=image_raw</argument>
<argument>camera_info:=camera_info</argument>
</ros>
<camera_name>stereo_camera</camera_name>
<frame_name>camera_link_optical</frame_name>
<hack_baseline>0.12</hack_baseline>
</plugin>
</sensor>
</gazebo>
With Ignition, it is a little bit different. You have to:
- attach a sensor to the camera_link for each camera
- set the sensor type to camera
- make them publish at the same rate (see https://gazebosim.org/docs/citadel/comparison#sensors)
- add a sensor plugin to the model/robot
- the baseline is set automatically thanks to the cameras pose (see https://github.com/gazebosim/gz-sim/blob/3b6c0f2a0bc71c5ff391852615609deec3c03674/src/systems/sensors/Sensors.cc#L746-L750)
Here is an example of stereo camera for Gazebo classic:
</gazebo>
<plugin name="ignition::gazebo::systems::Sensors" filename="libignition-gazebo-sensors-system.so">
</plugin>
</gazebo>
<gazebo reference="camera_link">
<sensor type="camera" name="left">
<update_rate>10.0</update_rate>
<always_on>true</always_on>
<pose>0 0 0 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>1024</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
</sensor>
<sensor type="camera" name="right">
<update_rate>10.0</update_rate>
<always_on>true</always_on>
<pose>0 -0.12 0 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>1024</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
</sensor>
</gazebo>
2 | No.2 Revision |
Thank you for your answers.
I was rather looking for how to define a stereo camera (not how to visualize it), but the answer was interesting.
The old way of adding stereo cameras in Gazebo classic was to:
- attach a sensor to the camera_link
- set the sensor type to multicamera
- define two cameras in this sensor using the << camera >> tag
- add a plugin to the sensor
- explicitly set the baseline in the plugin using the << hack_baseline >> tag
Here is an example of stereo camera for Gazebo classic:
<gazebo reference="camera_link">
<sensor type="multicamera" name="stereo_camera">
<update_rate>10.0</update_rate>
<always_on>true</always_on>
<camera name="left">
<pose>0 0 0 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>1024</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.0</stddev>
</noise>
<distortion>
<k1>0.0</k1>
<k2>0.0</k2>
<k3>0.0</k3>
<p1>0.0</p1>
<p2>0.0</p2>
<center>0.5 0.5</center>
</distortion>
</camera>
<camera name="right">
<pose>0 -0.12 0 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>1024</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.0</stddev>
</noise>
<distortion>
<k1>0.0</k1>
<k2>0.0</k2>
<k3>0.0</k3>
<p1>0.0</p1>
<p2>0.0</p2>
<center>0.5 0.5</center>
</distortion>
</camera>
<plugin name="stereo_camera_controller" filename="libgazebo_ros_camera.so">
<ros>
<namespace></namespace>
<argument>image_raw:=image_raw</argument>
<argument>camera_info:=camera_info</argument>
</ros>
<camera_name>stereo_camera</camera_name>
<frame_name>camera_link_optical</frame_name>
<hack_baseline>0.12</hack_baseline>
</plugin>
</sensor>
</gazebo>
With Ignition, it is a little bit different. You have to:
- attach a sensor to the camera_link for each camera
- set the sensor type to camera
- make them publish at the same rate (see https://gazebosim.org/docs/citadel/comparison#sensors)
- add a sensor plugin to the model/robot
- the baseline is set automatically thanks to the cameras pose (see https://github.com/gazebosim/gz-sim/blob/3b6c0f2a0bc71c5ff391852615609deec3c03674/src/systems/sensors/Sensors.cc#L746-L750)
Here is an example of stereo camera for Gazebo classic: Ignition:
</gazebo>
<plugin name="ignition::gazebo::systems::Sensors" filename="libignition-gazebo-sensors-system.so">
</plugin>
</gazebo>
<gazebo reference="camera_link">
<sensor type="camera" name="left">
<update_rate>10.0</update_rate>
<always_on>true</always_on>
<pose>0 0 0 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>1024</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
</sensor>
<sensor type="camera" name="right">
<update_rate>10.0</update_rate>
<always_on>true</always_on>
<pose>0 -0.12 0 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>1024</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
</sensor>
</gazebo>
3 | No.3 Revision |
Thank you for your answers.
I was rather looking for how to define a stereo camera (not how to visualize it), but the answer was interesting.
The old way of adding stereo cameras in Gazebo classic was to:
- attach a sensor to the camera_link
- set the sensor type to multicamera
- define two cameras in this sensor using the << camera >> tag
- add a plugin to the sensor
- explicitly set the baseline in the plugin using the << hack_baseline >> tag
Here is an example of stereo camera for Gazebo classic:
<gazebo reference="camera_link">
<sensor type="multicamera" name="stereo_camera">
<update_rate>10.0</update_rate>
<always_on>true</always_on>
<camera name="left">
<pose>0 0 0 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>1024</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.0</stddev>
</noise>
<distortion>
<k1>0.0</k1>
<k2>0.0</k2>
<k3>0.0</k3>
<p1>0.0</p1>
<p2>0.0</p2>
<center>0.5 0.5</center>
</distortion>
</camera>
<camera name="right">
<pose>0 -0.12 0 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>1024</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.0</stddev>
</noise>
<distortion>
<k1>0.0</k1>
<k2>0.0</k2>
<k3>0.0</k3>
<p1>0.0</p1>
<p2>0.0</p2>
<center>0.5 0.5</center>
</distortion>
</camera>
<plugin name="stereo_camera_controller" filename="libgazebo_ros_camera.so">
<ros>
<namespace></namespace>
<argument>image_raw:=image_raw</argument>
<argument>camera_info:=camera_info</argument>
</ros>
<camera_name>stereo_camera</camera_name>
<frame_name>camera_link_optical</frame_name>
<hack_baseline>0.12</hack_baseline>
</plugin>
</sensor>
</gazebo>
With Ignition, it is a little bit different. You have to:
- attach a sensor to the camera_link for each camera
- set the sensor type to camera
- make them publish at the same rate (see https://gazebosim.org/docs/citadel/comparison#sensors)
- add a sensor plugin to the model/robot
- the baseline is set automatically thanks to the cameras pose (see https://github.com/gazebosim/gz-sim/blob/3b6c0f2a0bc71c5ff391852615609deec3c03674/src/systems/sensors/Sensors.cc#L746-L750)
Here is an example of stereo camera for Gazebo Ignition:
</gazebo>
<plugin name="ignition::gazebo::systems::Sensors" filename="libignition-gazebo-sensors-system.so">
filename="libignition-gazebo-sensors-system.so"> </plugin>
</gazebo>
<gazebo reference="camera_link">
<sensor type="camera" name="right">
<update_rate>10.0</update_rate>
<always_on>true</always_on>
<ignition_frame_id>camera_link_optical</ignition_frame_id>
<pose>0 -0.12 0 0 0 0</pose>
<topic>stereo_camera/right/image_raw</topic>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>1024</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
</sensor>
<sensor type="camera" name="left">
<topic>stereo_camera/left/image_raw</topic>
<update_rate>10.0</update_rate>
<always_on>true</always_on>
<ignition_frame_id>camera_link_optical</ignition_frame_id>
<pose>0 0 0 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>1024</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
</sensor>
<sensor type="camera" name="right">
<update_rate>10.0</update_rate>
<always_on>true</always_on>
<pose>0 -0.12 0 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>1024</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
</sensor>
</gazebo>
</gazebo>
4 | No.4 Revision |
Thank you for your answers.
I was rather looking for how to define a stereo camera (not how to visualize it), but the answer was interesting.
The old way of adding stereo cameras in Gazebo classic was to:
- attach a sensor to the camera_link
- set the sensor type to multicamera
- define two cameras in this sensor using the << camera >> tag
- add a plugin to the sensor
- explicitly set the baseline in the plugin using the << hack_baseline >> tag
Here is an example of stereo camera for Gazebo classic:
<gazebo reference="camera_link">
<sensor type="multicamera" name="stereo_camera">
<update_rate>10.0</update_rate>
<always_on>true</always_on>
<camera name="left">
<pose>0 0 0 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>1024</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.0</stddev>
</noise>
<distortion>
<k1>0.0</k1>
<k2>0.0</k2>
<k3>0.0</k3>
<p1>0.0</p1>
<p2>0.0</p2>
<center>0.5 0.5</center>
</distortion>
</camera>
<camera name="right">
<pose>0 -0.12 0 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>1024</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.0</stddev>
</noise>
<distortion>
<k1>0.0</k1>
<k2>0.0</k2>
<k3>0.0</k3>
<p1>0.0</p1>
<p2>0.0</p2>
<center>0.5 0.5</center>
</distortion>
</camera>
<plugin name="stereo_camera_controller" filename="libgazebo_ros_camera.so">
<ros>
<namespace></namespace>
<argument>image_raw:=image_raw</argument>
<argument>camera_info:=camera_info</argument>
</ros>
<camera_name>stereo_camera</camera_name>
<frame_name>camera_link_optical</frame_name>
<hack_baseline>0.12</hack_baseline>
</plugin>
</sensor>
</gazebo>
With Ignition, it is a little bit different. You have to:
- attach a sensor to the camera_link for each camera
- set the sensor type to camera
- make them publish at the same rate (see https://gazebosim.org/docs/citadel/comparison#sensors)
- add a sensor plugin to the model/robot
- the baseline is set automatically thanks to the cameras pose (see https://github.com/gazebosim/gz-sim/blob/3b6c0f2a0bc71c5ff391852615609deec3c03674/src/systems/sensors/Sensors.cc#L746-L750)
Here is an example of stereo camera for Gazebo Ignition:
</gazebo>
<plugin name="ignition::gazebo::systems::Sensors" filename="libignition-gazebo-sensors-system.so"> </plugin>
</gazebo>
<gazebo reference="camera_link">
<sensor type="camera" name="right">
<update_rate>10.0</update_rate>
<always_on>true</always_on>
<ignition_frame_id>camera_link_optical</ignition_frame_id>
<pose>0 -0.12 0 0 0 0</pose>
<topic>stereo_camera/right/image_raw</topic>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>1024</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
</sensor>
<sensor type="camera" name="left">
<topic>stereo_camera/left/image_raw</topic>
<update_rate>10.0</update_rate>
<always_on>true</always_on>
<ignition_frame_id>camera_link_optical</ignition_frame_id>
<pose>0 0 0 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>1024</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
</sensor>
</gazebo>
</gazebo>