具体格式要求可参考:http://sdformat.org/spec?ver=1.6&elem=sdf
<?xml version="1.0" ?>
<sdf version="1.5">
<world name="default">
<light name='sun' type='directional'>
<cast_shadows>1</cast_shadows>
<pose>-11.82075 -19.38429 17.2198 0 -0 0</pose>
<diffuse>0.7 0.7 0.7 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.3698 0.4 -0.5</direction>
</light>
<model name="ground">
<static>true</static>
<link name="link">
<pose>-6.2343 -8.1302 0 0 -0 0</pose>
<visual name="visual">
<cast_shadows>false</cast_shadows>
<pose>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<uri>model://xxx_3D_visual.dae</uri>
<scale>1 1 1</scale>
</mesh>
</geometry>
</visual>
<collision name="collision">
<pose>0 0 0 0 0 0</pose>
<geometry>
<mesh>
<uri>model://xxx_3D_collision.stl</uri>
<scale>1 1 1</scale>
</mesh>
</geometry>
</collision>
</link>
</model>
<scene>
<ambient>0.4 0.4 0.4 1</ambient>
<background>0.7 0.7 0.7 1</background>
<shadows>1</shadows>
</scene>
</world>
</sdf>
world文件与机器人model模型属性定义类似,可以引用3D的mesh文件比如.dae .stl等作为visual或者collision,并可以定义物理环境条件等。
Husky官方地址:http://wiki.ros.org/Robots/Husky
这里的Husky模型被缩小了,比原来的机器人小很多,参数不一致!大约1/3
<?xml version='1.0'?>
<sdf version='1.6'>
<model name='xxx_husky'>
<link name='base_link'>
<inertial>
<mass>3.3855</mass>
<pose frame=''>-0.085613 -0.00084 0.1 0 -0 0</pose>
<inertia>
<ixx>0.22343</ixx>
<ixy>0</ixy>
<ixz>0.0275174</ixz>
<iyy>0.342518</iyy>
<iyz>0.00023962</iyz>
<izz>0.21241</izz>
</inertia>
</inertial>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
<pose frame=''>0 0 0.02 0 -0 0</pose>
<gravity>1</gravity>
<visual name='body'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<uri>model://husky/meshes/body.dae</uri>
<scale>0.33 0.33 0.3</scale>
</mesh>
</geometry>
</visual>
<collision name='collision'>
<laser_retro>0</laser_retro>
<max_contacts>10</max_contacts>
<pose frame=''>0 0 0.05 0 -0 0</pose>
<geometry>
<box>
<size>0.33 0.16 0.06</size>
</box>
</geometry>
</collision>
</link>
<link name='back_left_wheel'>
<pose frame=''>-0.09 0.1 0.035 0 -0 0</pose>
<inertial>
<mass>0.26357</mass>
<pose frame=''>0 0 0 0 -0 0</pose>
<inertia>
<ixx>0.00246688</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.00246688</iyy>
<iyz>0</iyz>
<izz>0.00441058</izz>
</inertia>
</inertial>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
<gravity>1</gravity>
<visual name='back_left_wheel'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<uri>model://husky/meshes/wheel.dae</uri>
<scale>0.3 0.3 0.3</scale>
</mesh>
</geometry>
</visual>
<collision name='back_left_wheel_collision'>
<laser_retro>0</laser_retro>
<max_contacts>10</max_contacts>
<pose frame=''>0 0 0 -1.5707 0 0</pose>
<geometry>
<cylinder>
<radius>0.055</radius>
<length>0.03</length>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>0.5</mu>
<mu2>50</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0.01</slip1>
<slip2>0</slip2>
</ode>
</friction>
</surface>
</collision>
</link>
<link name='back_right_wheel'>
<pose frame=''>-0.09 -0.1 0.035 0 -0 0</pose>
<inertial>
<mass>0.26357</mass>
<pose frame=''>0 0 0 0 -0 0</pose>
<inertia>
<ixx>0.00246688</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.00246688</iyy>
<iyz>0</iyz>
<izz>0.00441058</izz>
</inertia>
</inertial>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
<gravity>1</gravity>
<visual name='back_right_wheel'>
<pose frame=''>0 0 0 -3.14159 0 0</pose>
<geometry>
<mesh>
<uri>model://husky/meshes/wheel.dae</uri>
<scale>0.3 0.3 0.3</scale>
</mesh>
</geometry>
</visual>
<collision name='back_right_wheel_collision'>
<laser_retro>0</laser_retro>
<max_contacts>10</max_contacts>
<pose frame=''>0 0 0 -1.5707 0 0</pose>
<geometry>
<cylinder>
<radius>0.055</radius>
<length>0.03</length>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>0.5</mu>
<mu2>50</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0.01</slip1>
<slip2>0</slip2>
</ode>
</friction>
</surface>
</collision>
</link>
<link name='front_left_wheel'>
<pose frame=''>0.09 0.1 0.035 0 -0 0</pose>
<inertial>
<mass>0.26357</mass>
<pose frame=''>0 0 0 0 -0 0</pose>
<inertia>
<ixx>0.00246688</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.00246688</iyy>
<iyz>0</iyz>
<izz>0.00441058</izz>
</inertia>
</inertial>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
<gravity>1</gravity>
<visual name='front_left_wheel'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<uri>model://husky/meshes/wheel.dae</uri>
<scale>0.3 0.3 0.3</scale>
</mesh>
</geometry>
</visual>
<collision name='front_left_wheel_collision'>
<laser_retro>0</laser_retro>
<max_contacts>10</max_contacts>
<pose frame=''>0 0 0 -1.5707 0 0</pose>
<geometry>
<cylinder>
<radius>0.055</radius>
<length>0.03</length>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>0.5</mu>
<mu2>50</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0.01</slip1>
<slip2>0</slip2>
</ode>
</friction>
</surface>
</collision>
</link>
<link name='front_right_wheel'>
<pose frame=''>0.09 -0.1 0.035 0 -0 0</pose>
<inertial>
<mass>0.26357</mass>
<pose frame=''>0 0 0 0 -0 0</pose>
<inertia>
<ixx>0.00246688</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.00246688</iyy>
<iyz>0</iyz>
<izz>0.00441058</izz>
</inertia>
</inertial>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
<gravity>1</gravity>
<visual name='front_right_wheel'>
<pose frame=''>0 0 0 -3.14159 0 0</pose>
<geometry>
<mesh>
<uri>model://husky/meshes/wheel.dae</uri>
<scale>0.3 0.3 0.3</scale>
</mesh>
</geometry>
</visual>
<collision name='front_right_wheel_collision'>
<laser_retro>0</laser_retro>
<max_contacts>10</max_contacts>
<pose frame=''>0 0 0 -1.5707 0 0</pose>
<geometry>
<cylinder>
<radius>0.055</radius>
<length>0.03</length>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>0.5</mu>
<mu2>50</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0.01</slip1>
<slip2>0</slip2>
</ode>
</friction>
</surface>
</collision>
</link>
<link name='ray_sensor'>
<pose frame=''>0 0 0.09 0 -0 0</pose>
<sensor name='head_hokuyo_sensor' type='ray'>
<visualize>0</visualize>
<update_rate>10</update_rate>
<ray>
<scan>
<horizontal>
<samples>720</samples>
<resolution>1</resolution>
<min_angle>-3.14159</min_angle>
<max_angle>3.14159</max_angle>
</horizontal>
<vertical>
<samples>1</samples>
<min_angle>0</min_angle>
<max_angle>0</max_angle>
</vertical>
</scan>
<range>
<min>0.1</min>
<max>16</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name='gazebo_ros_head_hokuyo_controller' filename='libgazebo_ros_laser.so'>
<topicName>laser_scan</topicName>
<frameName>base_link</frameName>
</plugin>
</sensor>
<self_collide>0</self_collide>
<inertial>
<pose frame=''>0 0 0 0 -0 0</pose>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
<mass>1</mass>
</inertial>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
<gravity>1</gravity>
<visual name='ray_sensor_visual'>
<pose frame=''>0 0 0 1.5708 0 -1.5708</pose>
<geometry>
<mesh>
<uri>model://husky/meshes/eye_vision_camera.dae</uri>
<scale>0.2 0.2 0.2</scale>
</mesh>
</geometry>
</visual>
<collision name='ray_sensor_collision'>
<laser_retro>0</laser_retro>
<max_contacts>10</max_contacts>
<pose frame=''>0 0 0.015 0 -0 0</pose>
<geometry>
<cylinder>
<radius>0.01</radius>
<length>0.03</length>
</cylinder>
</geometry>
</collision>
</link>
<joint name='back_left_joint' type='revolute'>
<parent>base_link</parent>
<child>back_left_wheel</child>
<pose frame=''>0 0 0 0 -0 0</pose>
<axis>
<xyz>0 1 0</xyz>
<use_parent_model_frame>1</use_parent_model_frame>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
<effort>-1</effort>
<velocity>-1</velocity>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
<damping>0</damping>
<friction>0</friction>
</dynamics>
</axis>
<physics>
<ode>
<limit>
<cfm>0</cfm>
<erp>0.9</erp>
</limit>
<suspension>
<cfm>0</cfm>
<erp>0.2</erp>
</suspension>
</ode>
</physics>
</joint>
<joint name='back_right_joint' type='revolute'>
<parent>base_link</parent>
<child>back_right_wheel</child>
<pose frame=''>0 0 0 0 -0 0</pose>
<axis>
<xyz>0 1 0</xyz>
<use_parent_model_frame>1</use_parent_model_frame>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
<effort>-1</effort>
<velocity>-1</velocity>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
<damping>0</damping>
<friction>0</friction>
</dynamics>
</axis>
<physics>
<ode>
<limit>
<cfm>0</cfm>
<erp>0.9</erp>
</limit>
<suspension>
<cfm>0</cfm>
<erp>0.2</erp>
</suspension>
</ode>
</physics>
</joint>
<joint name='front_left_joint' type='revolute'>
<parent>base_link</parent>
<child>front_left_wheel</child>
<pose frame=''>0 0 0 0 -0 0</pose>
<axis>
<xyz>0 1 0</xyz>
<use_parent_model_frame>1</use_parent_model_frame>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
<effort>-1</effort>
<velocity>-1</velocity>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
<damping>0</damping>
<friction>0</friction>
</dynamics>
</axis>
<physics>
<ode>
<limit>
<cfm>0</cfm>
<erp>0.9</erp>
</limit>
<suspension>
<cfm>0</cfm>
<erp>0.2</erp>
</suspension>
</ode>
</physics>
</joint>
<joint name='front_right_joint' type='revolute'>
<parent>base_link</parent>
<child>front_right_wheel</child>
<pose frame=''>0 0 0 0 -0 0</pose>
<axis>
<xyz>0 1 0</xyz>
<use_parent_model_frame>1</use_parent_model_frame>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
<effort>-1</effort>
<velocity>-1</velocity>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
<damping>0</damping>
<friction>0</friction>
</dynamics>
</axis>
<physics>
<ode>
<limit>
<cfm>0</cfm>
<erp>0.9</erp>
</limit>
<suspension>
<cfm>0</cfm>
<erp>0.2</erp>
</suspension>
</ode>
</physics>
</joint>
<joint name='ray_sensor_joint' type='fixed'>
<parent>base_link</parent>
<child>ray_sensor</child>
<pose frame=''>0 0 0 0 -0 0</pose>
<physics>
<ode>
<limit>
<cfm>0</cfm>
<erp>0.2</erp>
</limit>
<suspension>
<cfm>0</cfm>
<erp>0.2</erp>
</suspension>
</ode>
</physics>
</joint>
<static>0</static>
<allow_auto_disable>1</allow_auto_disable>
<plugin name='husky_diff_controller' filename='libhusky_gazebo_plugins.so'>
<alwaysOn>1</alwaysOn>
<updateRate>50.0</updateRate>
<backLeftJoint>back_left_joint</backLeftJoint>
<backRightJoint>back_right_joint</backRightJoint>
<frontLeftJoint>front_left_joint</frontLeftJoint>
<frontRightJoint>front_right_joint</frontRightJoint>
<wheelSeparation>0.2</wheelSeparation>
<wheelDiameter>0.11</wheelDiameter>
<torque>5</torque>
</plugin>
<plugin name='p3d_base_controller' filename='libgazebo_ros_p3d.so'>
<alwaysOn>1</alwaysOn>
<updateRate>50.0</updateRate>
<bodyName>base_link</bodyName>
<topicName>base_pose_ground_truth</topicName>
<gaussianNoise>0</gaussianNoise>
<frameName>map</frameName>
<xyzOffsets>0 0 0</xyzOffsets>
<rpyOffsets>0 0 0</rpyOffsets>
</plugin>
</model>
</sdf>
model.sdf文件一般保存到.gazebo/models/中。
可以在gazeb中使用model editor进行编辑和查看
如何启动world文件:rosrun gazebo_ros gazebo xxx.world
然后加载机器人模型!