1. world环境搭建
- 模型可以随便放,但是如果要加载PX4仿真,在world中一定要加下面的物理模型,不然飞机加载不进去
<physics name='default_physics' default='0' type='ode'> <gravity>0 0 -9.8066</gravity> <ode> <solver> <type>quick</type> <iters>10</iters> <sor>1.3</sor> <use_dynamic_moi_rescaling>0</use_dynamic_moi_rescaling> </solver> <constraints> <cfm>0</cfm> <erp>0.2</erp> <contact_max_correcting_vel>100</contact_max_correcting_vel> <contact_surface_layer>0.001</contact_surface_layer> </constraints> </ode> <max_step_size>0.004</max_step_size> <real_time_factor>1</real_time_factor> <real_time_update_rate>250</real_time_update_rate> <magnetic_field>6.0e-6 2.3e-5 -4.2e-5</magnetic_field> </physics>
- 一个完整的world例子如下所示:
<?xml version="1.0" ?> <sdf version="1.6"> <world name="default"> <scene> <grid>false</grid> <origin_visual>false</origin_visual> <ambient>0.592 0.624 0.635 1</ambient> <sky> <clouds> <speed>12</speed> </clouds> </sky> <background>0.35 0.35 0.35 1.0</background> </scene> <physics name='default_physics' default='0' type='ode'> <gravity>0 0 -9.8066</gravity> <ode> <solver> <type>quick</type> <iters>10</iters> <sor>1.3</sor> <use_dynamic_moi_rescaling>0</use_dynamic_moi_rescaling> </solver> <constraints> <cfm>0</cfm> <erp>0.2</erp> <contact_max_correcting_vel>100</contact_max_correcting_vel> <contact_surface_layer>0.001</contact_surface_layer> </constraints> </ode> <max_step_size>0.004</max_step_size> <real_time_factor>1</real_time_factor> <real_time_update_rate>250</real_time_update_rate> <magnetic_field>6.0e-6 2.3e-5 -4.2e-5</magnetic_field> </physics> <spherical_coordinates> <surface_model>EARTH_WGS84</surface_model> <latitude_deg>0</latitude_deg> <longitude_deg>0</longitude_deg> <elevation>0</elevation> <heading_deg>0</heading_deg> </spherical_coordinates> <!-- A global light source --> <light type="directional" name="sun"> <pose>0 0 1000 0 0 0</pose> <cast_shadows>true</cast_shadows> <diffuse>0.8 0.8 0.8 1</diffuse> <specular>0.5 0.5 0.5 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.4</direction> </light> <model name="shaderbox"> <pose>0 0 -5 0 0 0</pose> <static>true</static> <link name="link"> <visual name="visual"> <geometry> <box> <size>0.1 0.1 0.1</size> </box> </geometry> <material> <script> <uri>file://media/materials/scripts/citysim.material</uri> <name>CitySim/ShinyGrey</name> </script> </material> <plugin name="bloom" filename="libBloomVisualPlugin.so" /> <plugin name="lensflare" filename="libLensFlareVisualPlugin.so" /> </visual> </link> </model> <!-- Environment --> <include> <name>city_terrain_1</name> <pose> 0 0 5.01 0 0 0 </pose> <uri>model://city_terrain</uri> </include> <include> <name>ocean_2</name> <pose> 40 -20 3.0 0 0 0 </pose> <uri>model://ocean</uri> </include> <road name="road_y_1"> <width>7.4</width> <point>-45 -103.7 5.02</point> <point>-45 104.2 5.02</point> </road> <road name="road_y_2"> <width>7.4</width> <point>-15 -103.7 5.02</point> <point>-15 104.2 5.02</point> <material> <script> <uri>file://media/materials/scripts/gazebo.material</uri> <name>Gazebo/Residential</name> </script> </material> </road> </world> </sdf>
2. 加载带有Realsense相机的无人机
在现有的iris无人机sdf模型中,在iris.sdf
文件的
<plugin name='mavlink_interface' filename='libgazebo_mavlink_interface.so'>
之前,插入下面一段即可。注意其中需要对相机旋转,另外为了不让桨叶挡住视野,我特地把相机抬高并向前放置了一点。但为了好看(相机和无人机贴在一起,而不是在无人机上面悬浮着),在visual 中把太高的距离又减了回去。
<!-- add realsense camera -->
<link name="depth_camera_link">
<pose frame=''>0.12 0 0.1 0 0 0</pose>
<inertial>
<pose frame=''>0 0 0 0 0 0</pose>
<mass>0.01</mass>
<inertia>
<ixx>4.15e-6</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>2.407e-6</iyy>
<iyz>0</iyz>
<izz>2.407e-6</izz>
</inertia>
</inertial>
<visual name="visual">
<pose>-0.0 0.0 -0.1 1.57 0 1.57</pose>
<geometry>
<mesh>
<uri>model://realsense_camera/meshes/D435i.dae</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/White</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual>
<sensor name="depth_camera" type="depth">
<update_rate>30</update_rate>
<camera>
<horizontal_fov>1.5708</horizontal_fov>
<image>
<format>R8G8B8</format>
<width>640</width>
<height>480</height>
</image>
<clip>
<near>0.1</near>
<far>88</far>
</clip>
</camera>
<plugin filename="libgazebo_ros_openni_kinect.so" name="camera_controller">
<robotNamespace/>
<cameraName>camera</cameraName>
<alwaysOn>true</alwaysOn>
<updateRate>0</updateRate>
<pointCloudCutoff>0.4</pointCloudCutoff>
<pointCloudCutoffMax>50</pointCloudCutoffMax>
<imageTopicName>color/image_raw</imageTopicName>
<cameraInfoTopicName>color/camera_info</cameraInfoTopicName>
<depthImageTopicName>depth/image_raw</depthImageTopicName>
<depthImageCameraInfoTopicName>depth/camera_info</depthImageCameraInfoTopicName>
<pointCloudTopicName>depth/points</pointCloudTopicName>
<frameName>camera_link</frameName>
<distortion_k1>0.0</distortion_k1>
<distortion_k2>0.0</distortion_k2>
<distortion_k3>0.0</distortion_k3>
<distortion_t1>0.0</distortion_t1>
<distortion_t2>0.0</distortion_t2>
</plugin>
</sensor>
<sensor name="camera_imu" type="imu">
<always_on>1</always_on>
</sensor>
</link>
<joint name='depth_camera_joint' type='fixed'>
<child>depth_camera_link</child>
<parent>base_link</parent>
<pose>0.0 0 0 1.57 0 1.57</pose>
<axis>
<xyz>0 0 1</xyz>
<limit>
<upper>0</upper>
<lower>0</lower>
</limit>
</axis>
</joint>