1 | initial version |
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</property>
<property type="double" key="height">300</property>
<property type="double" key="width">300</property>
<property type="double" key="x">300</property>
<property type="double" key="y">1</property>
<property type="double" key="z">1</property>
</ignition-gui>
</plugin>
</gui>
<light name='sun' type='directional'>
<cast_shadows>1</cast_shadows>
<pose>0 0 10 0 -0 0</pose>
<diffuse>1 1 1 1</diffuse>
<specular>0.5 0.5 0.5 1</specular>
<attenuation>
<range>1000</range>
<constant>0.90000000000000002</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
<spot>
<inner_angle>0</inner_angle>
<outer_angle>0</outer_angle>
<falloff>0</falloff>
</spot>
<visualize>false</visualize>
</light>
<gravity>0 0 0</gravity>
<magnetic_field>6e-06 2.3e-05 -4.2e-05</magnetic_field>
<atmosphere type='adiabatic'/>
<model name='auv'>
<link name='base_link'>
</link>
<link name='front_depth_camera'>
<pose>0.19 0.035 -0.08 0 0 1.57</pose>
<inertial>
<mass>1e-10</mass>
</inertial>
<visual name='front_depth_camera_visual'>
<geometry>
<box>
<size>0.01 0.01 0.01</size>
</box>
</geometry>
</visual>
<sensor type="depth_camera" name="front_depth_camera">
<update_rate>10</update_rate>
<camera>
<horizontal_fov>2.00</horizontal_fov>
<image>
<width>320</width>
<height>240</height>
<format>R_FLOAT32</format>
</image>
<clip>
<near>0.1</near>
<far>10.0</far>
</clip>
</camera>
</sensor>
</link>
<joint name='front_depth_camera_joint' type='fixed'>
<parent>base_link</parent>
<child>front_depth_camera</child>
</joint>
<link name='front_camera'>
<pose>0.19 0.035 -0.08 0 0 1.57</pose>
<inertial>
<mass>1e-10</mass>
</inertial>
<visual name='front_camera_visual'>
<geometry>
<box>
<size>0.01 0.01 0.01</size>
</box>
</geometry>
</visual>
<sensor type="camera" name="front_camera">
<update_rate>10</update_rate>
<camera>
<horizontal_fov>2.00</horizontal_fov>
<image>
<width>320</width>
<height>240</height>
</image>
<clip>
<near>0.1</near>
<far>10.0</far>
</clip>
</camera>
</sensor>
</link>
<joint name='front_camera_joint' type='fixed'>
<parent>base_link</parent>
<child>front_camera</child>
</joint>
</model>
<model name='ref_model'>
<link name='ref_link'>
<pose>0 1 0 0 0 0</pose>
<visual name='ref_visual'>
<geometry>
<box>
<size>0.1 0.1 0.1</size>
</box>
</geometry>
</visual>
</link>
</model>
<model name='ref_model2'>
<link name='ref_link2'>
<pose>-1 0 0 0 0 0</pose>
<visual name='ref_visual2'>
<geometry>
<box>
<size>0.1 0.1 0.1</size>
</box>
</geometry>
</visual>
</link>
</model>
</world> </sdf>