Initial Commit

This commit is contained in:
2026-02-09 03:39:49 +00:00
commit a756be4bf7
71 changed files with 6705 additions and 0 deletions

View File

@@ -0,0 +1,128 @@
<?xml version="1.0" ?>
<sdf version="1.6">
<model name="iris_with_camera">
<include>
<uri>model://iris</uri>
</include>
<link name="forward_camera_link">
<pose>0.1 0 0 0 0 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><box><size>0.02 0.02 0.02</size></box></geometry>
<material><ambient>0 0 0 1</ambient></material>
</visual>
<sensor name="forward_camera" type="camera">
<camera>
<horizontal_fov>1.57</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>R8G8B8</format>
</image>
<clip><near>0.1</near><far>100</far></clip>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>true</visualize>
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
<ros>
<namespace>/uav</namespace>
<remapping>image_raw:=camera/forward/image_raw</remapping>
<remapping>camera_info:=camera/forward/camera_info</remapping>
</ros>
<camera_name>forward_camera</camera_name>
<frame_name>forward_camera_link</frame_name>
</plugin>
</sensor>
</link>
<joint name="forward_camera_joint" type="fixed">
<parent>iris::base_link</parent>
<child>forward_camera_link</child>
</joint>
<link name="downward_camera_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><box><size>0.02 0.02 0.02</size></box></geometry>
<material><ambient>0.3 0.3 0.3 1</ambient></material>
</visual>
<sensor name="downward_camera" type="camera">
<camera>
<horizontal_fov>1.2</horizontal_fov>
<image>
<width>320</width>
<height>240</height>
<format>R8G8B8</format>
</image>
<clip><near>0.1</near><far>50</far></clip>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>false</visualize>
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
<ros>
<namespace>/uav</namespace>
<remapping>image_raw:=camera/downward/image_raw</remapping>
<remapping>camera_info:=camera/downward/camera_info</remapping>
</ros>
<camera_name>downward_camera</camera_name>
<frame_name>downward_camera_link</frame_name>
</plugin>
</sensor>
</link>
<joint name="downward_camera_joint" type="fixed">
<parent>iris::base_link</parent>
<child>downward_camera_link</child>
</joint>
<link name="rangefinder_link">
<pose>0 0 -0.06 0 1.5708 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="rangefinder" type="ray">
<ray>
<scan>
<horizontal><samples>1</samples><resolution>1</resolution><min_angle>0</min_angle><max_angle>0</max_angle></horizontal>
</scan>
<range><min>0.1</min><max>10</max><resolution>0.01</resolution></range>
</ray>
<always_on>1</always_on>
<update_rate>30</update_rate>
<plugin name="range_plugin" filename="libgazebo_ros_ray_sensor.so">
<ros>
<namespace>/uav</namespace>
<remapping>~/out:=rangefinder/range</remapping>
</ros>
<output_type>sensor_msgs/Range</output_type>
<frame_name>rangefinder_link</frame_name>
</plugin>
</sensor>
</link>
<joint name="rangefinder_joint" type="fixed">
<parent>iris::base_link</parent>
<child>rangefinder_link</child>
</joint>
</model>
</sdf>