ppovb5fc7/gazebo/test/worlds/multicamera_noisy_test.world

469 lines
12 KiB
XML

<?xml version="1.0" ?>
<sdf version="1.4">
<world name="default">
<include><uri>model://ground_plane</uri></include>
<include><uri>model://sun</uri></include>
<model name="multicamera_1">
<pose>0 0 0.5 0 0 0</pose>
<link name="link">
<collision name="collision">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</visual>
<sensor name="cam1" type="multicamera">
<update_rate>15</update_rate>
<camera name="left">
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>544</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>100</far>
</clip>
</camera>
</sensor>
</link>
</model>
<model name="multicamera_2">
<pose>0 0 0.5 0 0 0</pose>
<link name="link">
<collision name="collision">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</visual>
<sensor name="cam2" type="multicamera">
<update_rate>15</update_rate>
<camera name="left">
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>544</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>100</far>
</clip>
</camera>
<camera name="right">
<pose>0 -0.1 0 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>544</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>100</far>
</clip>
</camera>
</sensor>
</link>
</model>
<model name="multicamera_3">
<pose>2 0 0.5 0 0 0</pose>
<link name="link">
<collision name="collision">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</visual>
<sensor name="cam3" type="multicamera">
<update_rate>15</update_rate>
<camera name="top_left">
<pose>0 -0.1 0.1 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>544</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>100</far>
</clip>
</camera>
<camera name="top_right">
<pose>0 0.1 0.1 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>544</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>100</far>
</clip>
</camera>
<camera name="bottom_left">
<pose>0 -0.1 -0.1 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>544</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>100</far>
</clip>
</camera>
</sensor>
</link>
</model>
<model name="multicamera_4">
<pose>2 0 0.5 0 0 0</pose>
<link name="link">
<collision name="collision">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</visual>
<sensor name="cam4" type="multicamera">
<update_rate>15</update_rate>
<camera name="top_left">
<pose>0 -0.1 0.1 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>544</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>100</far>
</clip>
</camera>
<camera name="top_right">
<pose>0 0.1 0.1 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>544</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>100</far>
</clip>
</camera>
<camera name="bottom_left">
<pose>0 -0.1 -0.1 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>544</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>100</far>
</clip>
</camera>
<camera name="bottom_right">
<pose>0 0.1 -0.1 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>544</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>100</far>
</clip>
</camera>
</sensor>
</link>
</model>
<model name="multicamera_5">
<pose>2 0 0.5 0 0 0</pose>
<link name="link">
<collision name="collision">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</visual>
<sensor name="cam5" type="multicamera">
<update_rate>15</update_rate>
<camera name="top_left">
<pose>0 -0.1 0.1 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>544</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>100</far>
</clip>
</camera>
<camera name="top_right">
<pose>0 0.1 0.1 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>544</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>100</far>
</clip>
</camera>
<camera name="bottom_left">
<pose>0 -0.1 -0.1 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>544</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>100</far>
</clip>
</camera>
<camera name="bottom_right">
<pose>0 0.1 -0.1 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>544</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>100</far>
</clip>
</camera>
<camera name="bottom_right_2">
<pose>0 0.3 -0.1 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>544</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>100</far>
</clip>
</camera>
</sensor>
</link>
</model>
<model name="multicamera_6">
<pose>2 0 0.5 0 0 0</pose>
<link name="link">
<collision name="collision">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</visual>
<sensor name="cam6" type="multicamera">
<update_rate>15</update_rate>
<camera name="top_left">
<pose>0 -0.1 0.1 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>544</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>100</far>
</clip>
</camera>
<camera name="top_right">
<pose>0 0.1 0.1 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>544</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>100</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</camera>
<camera name="bottom_left">
<pose>0 -0.1 -0.1 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>544</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>100</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</camera>
<camera name="bottom_right">
<pose>0 0.1 -0.1 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>544</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>100</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.1</stddev>
</noise>
</camera>
<camera name="bottom_right_2">
<pose>0 0.3 -0.1 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>544</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>100</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>1</stddev>
</noise>
</camera>
<camera name="bottom_right_3">
<pose>0 0.3 -0.1 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>1024</width>
<height>544</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>100</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>10</stddev>
</noise>
</camera>
</sensor>
</link>
</model>
</world>
</sdf>