You cannot select more than 25 topics Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.

196 lines
5.0 KiB
Plaintext

4 years ago
<?xml version="1.0" ?>
<sdf version="1.6">
<world name="default">
<physics type="ode">
<ode>
<solver>
<type>quick</type>
<iters>100</iters>
<sor>1.0</sor>
</solver>
<constraints>
<cfm>0.0</cfm>
<erp>0.9</erp>
<contact_max_correcting_vel>0.1</contact_max_correcting_vel>
<contact_surface_layer>0.0</contact_surface_layer>
</constraints>
</ode>
<real_time_update_rate>-1</real_time_update_rate>
<!-- <max_step_size>0.0020</max_step_size> -->
</physics>
<include>
<uri>model://sun</uri>
</include>
<include>
<uri>model://ground_plane</uri>
</include>
<model name="iris">
<include>
<uri>model://iris_with_standoffs_demo</uri>
</include>
<!-- add new camera -->
<link name='camera'>
<pose>0 -0.01 0.070 1.57 0 1.57</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.1</mass>
<inertia>
<ixx>0.001</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.001</iyy>
<iyz>0</iyz>
<izz>0.001</izz>
</inertia>
</inertial>
<visual name='visual'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.025</radius>
<length>0.025</length>
</cylinder>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
<sensor name="camera" type="camera">
<pose>0 0 0 -1.57 -1.57 0</pose>
<camera>
<horizontal_fov>1.0472</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
</image>
<clip>
<near>0.05</near>
<far>1000</far>
</clip>
</camera>
<always_on>1</always_on>
<update_rate>10</update_rate>
<visualize>true</visualize>
<!-- <plugin name="irlock" filename="libArduCopterIRLockPlugin.so">
<fiducial>irlock_beacon_01</fiducial>
</plugin> -->
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
<cameraName>webcam</cameraName>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>camera_link</frameName>
<hackBaseline>0.07</hackBaseline>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
</plugin>
</sensor>
</link>
<!-- attach camera -->
<joint type="revolute" name="base_camera_joint">
<pose>0 0 0.0 0 0 0</pose>
<parent>iris::iris_demo::gimbal_small_2d::tilt_link</parent>
<child>camera</child>
<axis>
<limit>
<lower>0</lower>
<upper>0</upper>
</limit>
<xyz>0 0 1</xyz>
<use_parent_model_frame>true</use_parent_model_frame>
</axis>
</joint>
</model>
<model name="irlock_beacon_01">
<pose>1.0 -1.0 0.005 0 0 0</pose>
<link name="link">
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>3.0</mass>
<inertia>
<ixx>0.019</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.01</iyy>
<iyz>0</iyz>
<izz>0.01</izz>
</inertia>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>1.0 1.0 0.02</size>
</box>
</geometry>
<surface>
<friction>
<ode>
<mu>1.0</mu>
<mu2>1.0</mu2>
<fdir1>1 0 0</fdir1>
</ode>
</friction>
<contact>
<ode>
<kp>1e+12</kp>
<kd>1</kd>
<max_vel>10</max_vel>
<min_depth>0.003</min_depth>
</ode>
</contact>
</surface>
</collision>
<visual name="visual2">
<geometry>
<box>
<size>1.0 1.0 0.018</size>
</box>
</geometry>
<material>
<script>
<name>Gazebo/Green</name>
</script>
</material>
</visual>
<visual name="visual">
<geometry>
<box>
<size>0.1 0.1 0.02</size>
</box>
</geometry>
<material>
<script>
<name>Gazebo/Red</name>
</script>
</material>
</visual>
</link>
</model>
</world>
</sdf>