Created
January 8, 2021 19:31
-
-
Save JaldertVicarious/2800fda7fc8d52f019c6f58757b150cb to your computer and use it in GitHub Desktop.
An SDF file with multiple logical cameras
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
<sdf version="1.7"> | |
<!-- based on shapes.sdf example --> | |
<world name="multi_logical_camera"> | |
<physics name="physics_settings" type="dart"> | |
<max_step_size>0.001</max_step_size> | |
<real_time_factor>1.0</real_time_factor> | |
</physics> | |
<plugin filename="libignition-gazebo-physics-system.so" name="ignition::gazebo::systems::Physics"/> | |
<plugin filename="libignition-gazebo-user-commands-system.so" name="ignition::gazebo::systems::UserCommands"/> | |
<plugin filename="libignition-gazebo-scene-broadcaster-system.so" name="ignition::gazebo::systems::SceneBroadcaster"/> | |
<plugin filename="libignition-gazebo-sensors-system.so" name="ignition::gazebo::systems::Sensors"> | |
<render_engine>ogre2</render_engine> | |
</plugin> | |
<plugin filename="libignition-gazebo-logical-camera-system.so" name="ignition::gazebo::systems::LogicalCamera"> | |
<render_engine>ogre2</render_engine> | |
</plugin> | |
<plugin filename="libignition-gazebo-contact-system.so" name="ignition::gazebo::systems::Contact"/> | |
<scene> | |
<grid>true</grid> | |
<ambient>1.0 1.0 1.0</ambient> | |
<background>0.8 0.8 0.8</background> | |
</scene> | |
<gui fullscreen="0"> | |
<!-- 3D scene --> | |
<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>1.0 1.0 1.0</ambient_light> | |
<background_color>0.8 0.8 0.8</background_color> | |
<camera_pose>-6 0 6 0 0.5 0</camera_pose> | |
</plugin> | |
<!-- World control --> | |
<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> | |
<service>/world/multi_logical_camera/control</service> | |
<stats_topic>/world/multi_logical_camera/stats</stats_topic> | |
</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> | |
<topic>/world/multi_logical_camera/stats</topic> | |
</plugin> | |
<!-- Entity tree --> | |
<plugin filename="EntityTree" name="Entity tree"> | |
<ignition-gui> | |
<property type="bool" key="showTitleBar">false</property> | |
<property type="string" key="state">docked</property> | |
</ignition-gui> | |
</plugin> | |
<!-- Transform Control --> | |
<plugin filename="TransformControl" name="Transform Control"/> | |
<plugin filename="ImageDisplay" name="Image Display"> | |
<ignition-gui> | |
<property key="state" type="string">docked</property> | |
</ignition-gui> | |
</plugin> | |
</gui> | |
<light type="directional" name="sun"> | |
<cast_shadows>true</cast_shadows> | |
<pose>0 0 10 0 0 0</pose> | |
<diffuse>0.8 0.8 0.8 1</diffuse> | |
<specular>0.8 0.8 0.8 1</specular> | |
<attenuation> | |
<range>1000</range> | |
<constant>0.9</constant> | |
<linear>0.01</linear> | |
<quadratic>0.001</quadratic> | |
</attenuation> | |
<direction>-0.5 0.1 -0.9</direction> | |
</light> | |
<model name="ground_plane"> | |
<static>true</static> | |
<link name="link"> | |
<collision name="collision"> | |
<geometry> | |
<plane> | |
<normal>0 0 1</normal> | |
</plane> | |
</geometry> | |
</collision> | |
<visual name="visual"> | |
<geometry> | |
<plane> | |
<normal>0 0 1</normal> | |
<size>100 100</size> | |
</plane> | |
</geometry> | |
<material> | |
<ambient>0.8 0.8 0.8 1</ambient> | |
<diffuse>0.8 0.8 0.8 1</diffuse> | |
<specular>0.8 0.8 0.8 1</specular> | |
</material> | |
</visual> | |
</link> | |
</model> | |
<model name="box-1"> | |
<pose>-0.65 -0.65 0.05 0 0 0</pose> | |
<static>false</static> | |
<link name="body"> | |
<inertial> | |
<mass>0.25</mass> | |
<inertia> | |
<ixx>0.000416</ixx> | |
<ixy>0</ixy> | |
<ixz>0</ixz> | |
<iyy>0.000416</iyy> | |
<iyz>0</iyz> | |
<izz>0.000416</izz> | |
</inertia> | |
</inertial> | |
<visual name="visual"> | |
<geometry> | |
<box> | |
<size>.1 .1 .1</size> | |
</box> | |
</geometry> | |
<material> | |
<ambient>0.5 0.5 0.5 1</ambient> | |
<diffuse>0.5 0.5 0.5 1</diffuse> | |
<specular>0.5 0.5 0.5 1</specular> | |
</material> | |
</visual> | |
<collision name="collision"> | |
<geometry> | |
<box> | |
<size>.1 .1 .1</size> | |
</box> | |
</geometry> | |
</collision> | |
</link> | |
</model> | |
<model name="box-2"> | |
<pose>-0.838355 0.631337 0.05 -0 -0 -0</pose> | |
<static>false</static> | |
<link name="body"> | |
<inertial> | |
<mass>0.25</mass> | |
<inertia> | |
<ixx>0.000416</ixx> | |
<ixy>0</ixy> | |
<ixz>0</ixz> | |
<iyy>0.000416</iyy> | |
<iyz>0</iyz> | |
<izz>0.000416</izz> | |
</inertia> | |
</inertial> | |
<visual name="visual"> | |
<geometry> | |
<box> | |
<size>.1 .1 .1</size> | |
</box> | |
</geometry> | |
<material> | |
<ambient>0.5 0.5 0.5 1</ambient> | |
<diffuse>0.5 0.5 0.5 1</diffuse> | |
<specular>0.5 0.5 0.5 1</specular> | |
</material> | |
</visual> | |
<collision name="collision"> | |
<geometry> | |
<box> | |
<size>.1 .1 .1</size> | |
</box> | |
</geometry> | |
</collision> | |
</link> | |
</model> | |
<model name="logical_camera_1"> | |
<static>true</static> | |
<pose>-.75 -.75 2.0 0 1.57 0 </pose> | |
<link name="logical_camera_link"> | |
<pose>0 0 0 0 0 0</pose> | |
<collision name="collision"> | |
<geometry> | |
<box> | |
<size>0.1 0.1 0.1</size> | |
</box> | |
</geometry> | |
</collision> | |
<visual name="visual"> | |
<geometry> | |
<box> | |
<size>0.1 0.1 0.1</size> | |
</box> | |
</geometry> | |
</visual> | |
<sensor name="logical_camera_1" type="logical_camera"> | |
<topic>logical_camera_1</topic> | |
<update_rate>10</update_rate> | |
<logical_camera> | |
<near>0.55</near> | |
<far>5</far> | |
<horizontal_fov>1.04719755</horizontal_fov> | |
<aspect_ratio>1.778</aspect_ratio> | |
</logical_camera> | |
<alwaysOn>1</alwaysOn> | |
<visualize>true</visualize> | |
</sensor> | |
</link> | |
</model> | |
<model name="logical_camera_2"> | |
<static>true</static> | |
<pose>-.75 .75 2.0 0 1.57 0 </pose> | |
<link name="logical_camera_link"> | |
<pose>0 0 0 0 0 0</pose> | |
<collision name="collision"> | |
<geometry> | |
<box> | |
<size>0.1 0.1 0.1</size> | |
</box> | |
</geometry> | |
</collision> | |
<visual name="visual"> | |
<geometry> | |
<box> | |
<size>0.1 0.1 0.1</size> | |
</box> | |
</geometry> | |
</visual> | |
<sensor name="logical_camera_2" type="logical_camera"> | |
<topic>logical_camera_2</topic> | |
<update_rate>10</update_rate> | |
<logical_camera> | |
<near>0.55</near> | |
<far>5</far> | |
<horizontal_fov>1.04719755</horizontal_fov> | |
<aspect_ratio>1.778</aspect_ratio> | |
</logical_camera> | |
<alwaysOn>1</alwaysOn> | |
<visualize>true</visualize> | |
</sensor> | |
</link> | |
</model> | |
</world> | |
</sdf> |
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment