?docs: https://github.com/gazebosim/docs.gitgazebosim官方演示代码
<?xml version="1.0" ?>
<sdf version="1.8">
<world name="sensor_world">
<physics name="1ms" type="ignored">
<max_step_size>0.001</max_step_size>
<real_time_factor>1.0</real_time_factor>
</physics>
不带referrence属性的<plugin>就会直接插入到<world>内,从1.9开始没有<world>了
<plugin
filename="ignition-gazebo-physics-system"
name="ignition::gazebo::systems::Physics">
</plugin>
<plugin
filename="ignition-gazebo-user-commands-system"
name="ignition::gazebo::systems::UserCommands">
</plugin>
<plugin
filename="ignition-gazebo-scene-broadcaster-system"
name="ignition::gazebo::systems::SceneBroadcaster">
</plugin>
<plugin filename="ignition-gazebo-imu-system"
name="ignition::gazebo::systems::Imu">
</plugin>
<plugin filename="ignition-gazebo-sensors-system"
name="ignition::gazebo::systems::Sensors">
<render_engine>ogre2</render_engine>
</plugin>
<plugin filename="ignition-gazebo-contact-system"
name="ignition::gazebo::systems::Contact">
</plugin>
<gui fullscreen="0">
<!-- 3D scene -->
<plugin filename="MinimalScene" name="3D View">
<gz-gui>
<title>3D View</title>
<property type="bool" key="showTitleBar">false</property>
<property type="string" key="state">docked</property>
</gz-gui>
<engine>ogre2</engine>
<scene>scene</scene>
<ambient_light>0.4 0.4 0.4</ambient_light>
<background_color>0.8 0.8 0.8</background_color>
<camera_pose>-6 0 6 0 0.5 0</camera_pose>
<camera_clip>
<near>0.25</near>
<far>25000</far>
</camera_clip>
</plugin>
<!-- Plugins that add functionality to the scene -->
<plugin filename="EntityContextMenuPlugin" name="Entity context menu">
<gz-gui>
<property key="state" type="string">floating</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="GzSceneManager" name="Scene Manager">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="InteractiveViewControl" name="Interactive view control">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="CameraTracking" name="Camera Tracking">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="MarkerManager" name="Marker manager">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="SelectEntities" name="Select Entities">
<gz-gui>
<anchors target="Select entities">
<line own="right" target="right"/>
<line own="top" target="top"/>
</anchors>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="VisualizationCapabilities" name="Visualization Capabilities">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<plugin filename="Spawn" name="Spawn Entities">
<gz-gui>
<anchors target="Select entities">
<line own="right" target="right"/>
<line own="top" target="top"/>
</anchors>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</gz-gui>
</plugin>
<!-- World control -->
<plugin filename="WorldControl" name="World control">
<gz-gui>
<title>World control</title>
<property type="bool" key="showTitleBar">false</property>
<property type="bool" key="resizable">false</property>
<property type="double" key="height">72</property>
<property type="double" key="width">121</property>
<property type="double" key="z">1</property>
<property type="string" key="state">floating</property>
<anchors target="3D View">
<line own="left" target="left"/>
<line own="bottom" target="bottom"/>
</anchors>
</gz-gui>
<play_pause>true</play_pause>
<step>true</step>
<start_paused>true</start_paused>
<use_event>true</use_event>
</plugin>
<!-- World statistics -->
<plugin filename="WorldStats" name="World stats">
<gz-gui>
<title>World stats</title>
<property type="bool" key="showTitleBar">false</property>
<property type="bool" key="resizable">false</property>
<property type="double" key="height">110</property>
<property type="double" key="width">290</property>
<property type="double" key="z">1</property>
<property type="string" key="state">floating</property>
<anchors target="3D View">
<line own="right" target="right"/>
<line own="bottom" target="bottom"/>
</anchors>
</gz-gui>
<sim_time>true</sim_time>
<real_time>true</real_time>
<real_time_factor>true</real_time_factor>
<iterations>true</iterations>
</plugin>
<!-- Insert simple shapes -->
<plugin filename="Shapes" name="Shapes">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="x" type="double">0</property>
<property key="y" type="double">0</property>
<property key="width" type="double">250</property>
<property key="height" type="double">50</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
<property key="cardBackground" type="string">#666666</property>
</gz-gui>
</plugin>
<!-- Insert lights -->
<plugin filename="Lights" name="Lights">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="x" type="double">250</property>
<property key="y" type="double">0</property>
<property key="width" type="double">150</property>
<property key="height" type="double">50</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
<property key="cardBackground" type="string">#666666</property>
</gz-gui>
</plugin>
<!-- Translate / rotate -->
<plugin filename="TransformControl" name="Transform control">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="x" type="double">0</property>
<property key="y" type="double">50</property>
<property key="width" type="double">250</property>
<property key="height" type="double">50</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
<property key="cardBackground" type="string">#777777</property>
</gz-gui>
</plugin>
<!-- Screenshot -->
<plugin filename="Screenshot" name="Screenshot">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="x" type="double">250</property>
<property key="y" type="double">50</property>
<property key="width" type="double">50</property>
<property key="height" type="double">50</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
<property key="cardBackground" type="string">#777777</property>
</gz-gui>
</plugin>
<!-- Video recorder -->
<plugin filename="VideoRecorder" name="VideoRecorder">
<gz-gui>
<property key="resizable" type="bool">false</property>
<property key="x" type="double">300</property>
<property key="y" type="double">50</property>
<property key="width" type="double">50</property>
<property key="height" type="double">50</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
<property key="cardBackground" type="string">#777777</property>
</gz-gui>
<record_video>
<use_sim_time>true</use_sim_time>
<lockstep>false</lockstep>
<bitrate>4000000</bitrate>
</record_video>
</plugin>
<!-- Inspector -->
<plugin filename="ComponentInspector" name="Component inspector">
<gz-gui>
<property type="string" key="state">docked_collapsed</property>
</gz-gui>
</plugin>
<!-- Entity tree -->
<plugin filename="EntityTree" name="Entity tree">
<gz-gui>
<property type="string" key="state">docked_collapsed</property>
</gz-gui>
</plugin>
<!-- View angle -->
<plugin filename="ViewAngle" name="View angle">
<gz-gui>
<property type="string" key="state">docked_collapsed</property>
</gz-gui>
</plugin>
<!-- KeyPublisher plugin-->
<plugin filename="KeyPublisher" name="Key Publisher"/>
</gui>
<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.2 0.2 0.2 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.9</direction>
</light>
<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
</plane>
</geometry>
</collision>
<visual name="visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
</link>
</model>
<model name='vehicle_blue' canonical_link='chassis'>
<pose relative_to='world'>0 0 1 0 0 0</pose> <!--the pose is relative to the world by default-->
<frame name="lidar_frame" attached_to='chassis'>
<pose>0.8 0 0.5 0 0 0</pose>
</frame>
<link name='chassis'>
<pose relative_to='__model__'>0.5 0 0.4 0 0 0</pose>
<inertial> <!--inertial properties of the link mass, inertia matix-->
<mass>1.14395</mass>
<inertia>
<ixx>0.126164</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.416519</iyy>
<iyz>0</iyz>
<izz>0.481014</izz>
</inertia>
</inertial>
<visual name='visual'>
<geometry>
<box>
<size>2.0 1.0 0.5</size> <!--question: this size is in meter-->
</box>
</geometry>
<!--let's add color to our link-->
<material>
<ambient>0.0 0.0 1.0 1</ambient>
<diffuse>0.0 0.0 1.0 1</diffuse>
<specular>0.0 0.0 1.0 1</specular>
</material>
</visual>
<collision name='collision'> <!--todo: describe why we need the collision-->
<geometry>
<box>
<size>2.0 1.0 0.5</size>
</box>
</geometry>
</collision>
<sensor name="imu_sensor" type="imu">
<always_on>1</always_on>
<update_rate>1</update_rate>
<visualize>true</visualize>
<topic>imu</topic>
</sensor>
<sensor name='gpu_lidar' type='gpu_lidar'>"
<pose relative_to='lidar_frame'>0 0 0 0 0 0</pose>
<topic>lidar</topic>
<update_rate>10</update_rate>
<ray>
<scan>
<horizontal>
<samples>640</samples>
<resolution>1</resolution>
<min_angle>-1.396263</min_angle>
<max_angle>1.396263</max_angle>
</horizontal>
<vertical>
<samples>1</samples>
<resolution>0.01</resolution>
<min_angle>0</min_angle>
<max_angle>0</max_angle>
</vertical>
</scan>
<range>
<min>0.08</min>
<max>10.0</max>
<resolution>0.01</resolution>
</range>
</ray>
<alwaysOn>1</alwaysOn>
<visualize>true</visualize>
</sensor>
</link>
<!--let's build the left wheel-->
<link name='left_wheel'>
<pose relative_to="chassis">-0.5 0.6 0 -1.5707 0 0</pose> <!--angles are in radian-->
<inertial>
<mass>2</mass>
<inertia>
<ixx>0.145833</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.145833</iyy>
<iyz>0</iyz>
<izz>0.125</izz>
</inertia>
</inertial>
<visual name='visual'>
<geometry>
<cylinder>
<radius>0.4</radius>
<length>0.2</length>
</cylinder>
</geometry>
<material>
<ambient>1.0 0.0 0.0 1</ambient>
<diffuse>1.0 0.0 0.0 1</diffuse>
<specular>1.0 0.0 0.0 1</specular>
</material>
</visual>
<collision name='collision'>
<geometry>
<cylinder>
<radius>0.4</radius>
<length>0.2</length>
</cylinder>
</geometry>
</collision>
</link>
<!--copy and paste for right wheel but change position-->
<link name='right_wheel'>
<pose relative_to="chassis">-0.5 -0.6 0 -1.5707 0 0</pose> <!--angles are in radian-->
<inertial>
<mass>1</mass>
<inertia>
<ixx>0.145833</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.145833</iyy>
<iyz>0</iyz>
<izz>0.125</izz>
</inertia>
</inertial>
<visual name='visual'>
<geometry>
<cylinder>
<radius>0.4</radius>
<length>0.2</length>
</cylinder>
</geometry>
<material>
<ambient>1.0 0.0 0.0 1</ambient>
<diffuse>1.0 0.0 0.0 1</diffuse>
<specular>1.0 0.0 0.0 1</specular>
</material>
</visual>
<collision name='collision'>
<geometry>
<cylinder>
<radius>0.4</radius>
<length>0.2</length>
</cylinder>
</geometry>
</collision>
</link>
<frame name="caster_frame" attached_to='chassis'>
<pose>0.8 0 -0.2 0 0 0</pose>
</frame>
<!--caster wheel-->
<link name='caster'>
<pose relative_to='caster_frame'/>
<inertial>
<mass>1</mass>
<inertia>
<ixx>0.1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.1</iyy>
<iyz>0</iyz>
<izz>0.1</izz>
</inertia>
</inertial>
<visual name='visual'>
<geometry>
<sphere>
<radius>0.2</radius>
</sphere>
</geometry>
<material>
<ambient>0.0 1 0.0 1</ambient>
<diffuse>0.0 1 0.0 1</diffuse>
<specular>0.0 1 0.0 1</specular>
</material>
</visual>
<collision name='collision'>
<geometry>
<sphere>
<radius>0.2</radius>
</sphere>
</geometry>
</collision>
</link>
<!--connecting these links together using joints-->
<joint name='left_wheel_joint' type='revolute'> <!--continous joint is not supported yet-->
<pose relative_to='left_wheel'/>
<parent>chassis</parent>
<child>left_wheel</child>
<axis>
<xyz expressed_in='__model__'>0 1 0</xyz> <!--can be descired to any frame or even arbitrary frames-->
<limit>
<lower>-1.79769e+308</lower> <!--negative infinity-->
<upper>1.79769e+308</upper> <!--positive infinity-->
</limit>
</axis>
</joint>
<joint name='right_wheel_joint' type='revolute'>
<pose relative_to='right_wheel'/>
<parent>chassis</parent>
<child>right_wheel</child>
<axis>
<xyz expressed_in='__model__'>0 1 0</xyz>
<limit>
<lower>-1.79769e+308</lower> <!--negative infinity-->
<upper>1.79769e+308</upper> <!--positive infinity-->
</limit>
</axis>
</joint>
<!--different type of joints ball joint--> <!--defult value is the child-->
<joint name='caster_wheel' type='ball'>
<parent>chassis</parent>
<child>caster</child>
</joint>
<!--diff drive plugin-->
<plugin
filename="ignition-gazebo-diff-drive-system"
name="ignition::gazebo::systems::DiffDrive">
<left_joint>left_wheel_joint</left_joint>
<right_joint>right_wheel_joint</right_joint>
<wheel_separation>1.2</wheel_separation>
<wheel_radius>0.4</wheel_radius>
<odom_publish_frequency>1</odom_publish_frequency>
<topic>cmd_vel</topic>
</plugin>
</model>
<!--wall-->
<model name='wall'>
<static>true</static>
<pose>5 0 0 0 0 0</pose><!--pose relative to the world-->
<link name='box'>
<pose/>
<inertial> <!--inertial properties of the link mass, inertia matix-->
<mass>1.14395</mass>
<inertia>
<ixx>9.532917</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.023832</iyy>
<iyz>0</iyz>
<izz>9.556749</izz>
</inertia>
</inertial>
<visual name='visual'>
<geometry>
<box>
<size>0.5 10.0 2.0</size>
</box>
</geometry>
<!--let's add color to our link-->
<material>
<ambient>0.0 0.0 1.0 1</ambient>
<diffuse>0.0 0.0 1.0 1</diffuse>
<specular>0.0 0.0 1.0 1</specular>
</material>
</visual>
<collision name='collision'> <!--todo: describe why we need the collision-->
<geometry>
<box>
<size>0.5 10.0 2.0</size>
</box>
</geometry>
</collision>
<sensor name='sensor_contact' type='contact'>
<contact>
<collision>collision</collision>
</contact>
</sensor>
</link>
<plugin filename="ignition-gazebo-touchplugin-system"
name="ignition::gazebo::systems::TouchPlugin">
<target>vehicle_blue</target>
<namespace>wall</namespace>
<time>0.001</time>
<enabled>true</enabled>
</plugin>
</model>
<!-- Moving Forward-->
<plugin filename="ignition-gazebo-triggered-publisher-system"
name="ignition::gazebo::systems::TriggeredPublisher">
<input type="ignition.msgs.Int32" topic="/keyboard/keypress">
<match field="data">16777235</match>
</input>
<output type="ignition.msgs.Twist" topic="/cmd_vel">
linear: {x: 0.5}, angular: {z: 0.0}
</output>
</plugin>
<!-- Moving Backward-->
<plugin filename="ignition-gazebo-triggered-publisher-system"
name="ignition::gazebo::systems::TriggeredPublisher">
<input type="ignition.msgs.Int32" topic="/keyboard/keypress">
<match field="data">16777237</match>
</input>
<output type="ignition.msgs.Twist" topic="/cmd_vel">
linear: {x: -0.5}, angular: {z: 0.0}
</output>
</plugin>
<!-- Rotating right-->
<plugin filename="ignition-gazebo-triggered-publisher-system"
name="ignition::gazebo::systems::TriggeredPublisher">
<input type="ignition.msgs.Int32" topic="/keyboard/keypress">
<match field="data">16777236</match>
</input>
<output type="ignition.msgs.Twist" topic="/cmd_vel">
linear: {x: 0.0}, angular: {z: -0.5}
</output>
</plugin>
<!--Rotating left-->
<plugin filename="ignition-gazebo-triggered-publisher-system"
name="ignition::gazebo::systems::TriggeredPublisher">
<input type="ignition.msgs.Int32" topic="/keyboard/keypress">
<match field="data">16777234</match>
</input>
<output type="ignition.msgs.Twist" topic="/cmd_vel">
linear: {x: 0.0}, angular: {z: 0.5}
</output>
</plugin>
<!--stop when hit the wall-->
<plugin filename="ignition-gazebo-triggered-publisher-system"
name="ignition::gazebo::systems::TriggeredPublisher">
<input type="ignition.msgs.Boolean" topic="/wall/touched">
<match>data: true</match>
</input>
<output type="ignition.msgs.Twist" topic="/cmd_vel">
linear: {x: 0.0}, angular: {z: 0.0}
</output>
</plugin>
</world>
</sdf>