Gazebo | Ignition | Community
Ask Your Question
0

How to setup a stereo camera with ignition ?

asked 2022-05-23 08:59:42 -0500

Clement gravatar image

Hello,

Do you have any example of SDF file with stereo cameras ?

Thx

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
0

answered 2022-05-24 10:51:53 -0500

Clement gravatar image

updated 2022-05-24 10:57:56 -0500

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/co...)
- 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/b...)

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>
edit flag offensive delete link more

Comments

I'm not sure exactly what is this on ignition. It doesn't look like ignition sdf file to me. Ign doesn't use <gazebo>. If I remember right, classic uses it.

Are you sure you are using ignition?

kakcalu13 gravatar imagekakcalu13 ( 2022-05-27 07:43:51 -0500 )edit

Actually, I'm using URDF, and you can use the <gazebo> tag inside URDF to define the Ignition plugins to link to your robot frames.

Clement gravatar imageClement ( 2022-06-09 09:12:13 -0500 )edit
1

answered 2022-05-24 07:42:45 -0500

florian.pix gravatar image

You can first take a look at the sensors that are supported by sdformat. There you can find "camera", "depth_camera" and "multicamera". In the following example I am using "camera" and "depth_camera" to replicate the stereo camera functionality. I am not aware if "multicamera" is supported by ign gazebo and how you would use it, maybe someone else can add some more information about that.

<sdf version='1.8'>
<world name='auv'>
<scene>
  <sky>
    <clouds>
      <speed>12</speed>
    </clouds>
  </sky>
  <shadows>1</shadows>
  <fog>
    <color>0.05 0.2 0.2 1.0</color>
    <type>linear</type>
    <density>0.1</density>
    <start>1</start>
    <end>4</end>
  </fog>
  <ambient>0 1 1 1</ambient>
  <background>0 0.7 0.8 1</background>
  <shadows>1</shadows>
</scene>
<physics name='1ms' type='ode'>
  <max_step_size>0.001</max_step_size>
  <real_time_factor>1</real_time_factor>
  <real_time_update_rate>1000</real_time_update_rate>
</physics>
<plugin name='ignition::gazebo::systems::Physics' filename='ignition-gazebo-physics-system'/>
<plugin name='ignition::gazebo::systems::UserCommands' filename='ignition-gazebo-user-commands-system'/>
<plugin name='ignition::gazebo::systems::SceneBroadcaster' filename='ignition-gazebo-scene-broadcaster-system'/>
<plugin name="ignition::gazebo::systems::Sensors" filename="ignition-gazebo-sensors-system">
  <render_engine>ogre2</render_engine>
</plugin>

<gui>
  <plugin filename="GzScene3D" name="3D View">
    <ignition-gui>
      <title>3D View</title>
      <property type="bool" key="showTitleBar">false</property>
      <property type="string" key="state">docked</property>
    </ignition-gui>

    <engine>ogre2</engine>
    <scene>scene</scene>
    <ambient_light>0.4 0.4 0.4</ambient_light>
    <background_color>0.8 0.8 0.8</background_color>
    <camera_pose>0 1 1 0 0.5 -1.57</camera_pose>
  </plugin>

  <plugin filename="WorldControl" name="World control">
    <ignition-gui>
      <title>World control</title>
      <property type="bool" key="showTitleBar">false</property>
      <property type="bool" key="resizable">false</property>
      <property type="double" key="height">72</property>
      <property type="double" key="width">121</property>
      <property type="double" key="z">1</property>

      <property type="string" key="state">floating</property>
      <anchors target="3D View">
        <line own="left" target="left"/>
        <line own="bottom" target="bottom"/>
      </anchors>
    </ignition-gui>

    <play_pause>true</play_pause>
    <step>true</step>
    <start_paused>true</start_paused>
  </plugin>

  <!-- World statistics -->
  <plugin filename="WorldStats" name="World stats">
    <ignition-gui>
      <title>World stats</title>
      <property type="bool" key="showTitleBar">false</property>
      <property type="bool" key="resizable">false</property>
      <property type="double" key="height">110</property>
      <property type="double" key="width">290</property>
      <property type="double" key="z">1</property>

      <property type="string" key="state">floating</property>
      <anchors target="3D View">
        <line own="right" target="right"/>
        <line own="bottom" target="bottom"/>
      </anchors>
    </ignition-gui>

    <sim_time>true</sim_time>
    <real_time>true</real_time>
    <real_time_factor>true</real_time_factor>
    <iterations>true</iterations>
  </plugin>

  <plugin filename="ImageDisplay" name="front_depth_camera">
    <topic>/world/auv/model/auv/link/front_depth_camera/sensor/front_depth_camera/depth_image</topic>
    <topic_picker>0</topic_picker>
    <ignition-gui>
      <title>front depth camera</title>
      <property key="state" type="string">floating</property>
      <property type="double" key="height">300</property>
      <property type="double" key="width">300</property>
      <property type="double" key="x">1</property>
      <property type="double" key="y">1</property>
      <property type="double" key="z">1</property>
    </ignition-gui>
  </plugin>
  <plugin filename="ImageDisplay" name="front_camera">
    <topic>/world/auv/model/auv/link/front_camera/sensor/front_camera/image</topic>
    <topic_picker>0</topic_picker>
    <ignition-gui>
      <title>front camera</title>
      <property key="state" type="string">floating ...
(more)
edit flag offensive delete link more

Comments

This is correct method to use. You actually can use 3 camera at the same time as well through ign topic. I use them through ros2 foxy to ign. GUI may be limited to one per sensor however you can just duplicate them. See here for example: image description

But you can get them all at once through programming. See here:

{'sensory_data': {'ir': {1: True, 0: True, 2: True}, The name is changed to sensory_data.

kakcalu13 gravatar imagekakcalu13 ( 2022-05-24 08:58:23 -0500 )edit

So, the OP can just do his/her little art project then add the plugin like florian.pix mentioned.

Keep it in mind, you need to add a plugin per link (or model if you are too advanced already)

Your post is absolutely correct, IMO.

+1!

kakcalu13 gravatar imagekakcalu13 ( 2022-05-24 09:01:05 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2022-05-23 08:59:42 -0500

Seen: 1,469 times

Last updated: May 24 '22