Files
2026-02-09 03:39:49 +00:00

89 lines
3.0 KiB
XML

<?xml version="1.0" ?>
<sdf version="1.6">
<model name="iris_with_sensors">
<include>
<uri>model://iris</uri>
</include>
<link name="optical_flow_link">
<pose>0 0 -0.05 0 1.5708 0</pose>
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.00001</ixx><ixy>0</ixy><ixz>0</ixz>
<iyy>0.00001</iyy><iyz>0</iyz><izz>0.00001</izz>
</inertia>
</inertial>
<visual name="visual">
<geometry><cylinder><radius>0.01</radius><length>0.02</length></cylinder></geometry>
<material><ambient>0.2 0.2 0.2 1</ambient></material>
</visual>
<sensor name="optical_flow_camera" type="camera">
<camera>
<horizontal_fov>1.0</horizontal_fov>
<image>
<width>160</width>
<height>120</height>
<format>R8G8B8</format>
</image>
<clip><near>0.1</near><far>20</far></clip>
</camera>
<always_on>1</always_on>
<update_rate>60</update_rate>
<plugin name="optical_flow_plugin" filename="libgazebo_ros_camera.so">
<ros>
<namespace>/uav</namespace>
<remapping>image_raw:=optical_flow/image_raw</remapping>
</ros>
<camera_name>optical_flow</camera_name>
<frame_name>optical_flow_link</frame_name>
</plugin>
</sensor>
</link>
<joint name="optical_flow_joint" type="fixed">
<parent>iris::base_link</parent>
<child>optical_flow_link</child>
</joint>
<link name="imu_link">
<pose>0 0 0 0 0 0</pose>
<inertial>
<mass>0.005</mass>
<inertia>
<ixx>0.000001</ixx><ixy>0</ixy><ixz>0</ixz>
<iyy>0.000001</iyy><iyz>0</iyz><izz>0.000001</izz>
</inertia>
</inertial>
<sensor name="imu_sensor" type="imu">
<imu>
<angular_velocity>
<x><noise type="gaussian"><mean>0</mean><stddev>0.0002</stddev></noise></x>
<y><noise type="gaussian"><mean>0</mean><stddev>0.0002</stddev></noise></y>
<z><noise type="gaussian"><mean>0</mean><stddev>0.0002</stddev></noise></z>
</angular_velocity>
<linear_acceleration>
<x><noise type="gaussian"><mean>0</mean><stddev>0.017</stddev></noise></x>
<y><noise type="gaussian"><mean>0</mean><stddev>0.017</stddev></noise></y>
<z><noise type="gaussian"><mean>0</mean><stddev>0.017</stddev></noise></z>
</linear_acceleration>
</imu>
<always_on>1</always_on>
<update_rate>200</update_rate>
<plugin name="imu_plugin" filename="libgazebo_ros_imu_sensor.so">
<ros>
<namespace>/uav</namespace>
<remapping>~/out:=imu/data</remapping>
</ros>
<frame_name>imu_link</frame_name>
</plugin>
</sensor>
</link>
<joint name="imu_joint" type="fixed">
<parent>iris::base_link</parent>
<child>imu_link</child>
</joint>
</model>
</sdf>