<?xml version="1.0" ?><sdfversion="1.8"><worldname="Moving_robot"><physicsname="1ms"type="ignored"><max_step_size>0.001</max_step_size><real_time_factor>1.0</real_time_factor></physics><pluginfilename="gz-sim-physics-system"name="gz::sim::systems::Physics"></plugin><pluginfilename="gz-sim-user-commands-system"name="gz::sim::systems::UserCommands"></plugin><pluginfilename="gz-sim-scene-broadcaster-system"name="gz::sim::systems::SceneBroadcaster"></plugin><lighttype="directional"name="sun"><cast_shadows>true</cast_shadows><pose>0010000</pose><diffuse>0.80.80.81</diffuse><specular>0.20.20.21</specular><attenuation><range>1000</range><constant>0.9</constant><linear>0.01</linear><quadratic>0.001</quadratic></attenuation><direction>-0.50.1-0.9</direction></light><modelname="ground_plane"><static>true</static><linkname="link"><collisionname="collision"><geometry><plane><normal>001</normal></plane></geometry></collision><visualname="visual"><geometry><plane><normal>001</normal><size>100100</size></plane></geometry><material><ambient>0.80.80.81</ambient><diffuse>0.80.80.81</diffuse><specular>0.80.80.81</specular></material></visual></link></model><modelname='vehicle_blue'canonical_link='chassis'><poserelative_to='world'>000000</pose><!--the pose is relative to the world by default--><linkname='chassis'><poserelative_to='__model__'>0.500.4000</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><visualname='visual'><geometry><box><size>2.01.00.5</size><!--question: this size is in meter--></box></geometry><!--let's add color to our link--><material><ambient>0.00.01.01</ambient><diffuse>0.00.01.01</diffuse><specular>0.00.01.01</specular></material></visual><collisionname='collision'><!--todo: describe why we need the collision--><geometry><box><size>2.01.00.5</size></box></geometry></collision></link><!--let's build the left wheel--><linkname='left_wheel'><poserelative_to="chassis">-0.50.60-1.570700</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><visualname='visual'><geometry><cylinder><radius>0.4</radius><length>0.2</length></cylinder></geometry><material><ambient>1.00.00.01</ambient><diffuse>1.00.00.01</diffuse><specular>1.00.00.01</specular></material></visual><collisionname='collision'><geometry><cylinder><radius>0.4</radius><length>0.2</length></cylinder></geometry></collision></link><!--copy and paste for right wheel but change position--><linkname='right_wheel'><poserelative_to="chassis">-0.5-0.60-1.570700</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><visualname='visual'><geometry><cylinder><radius>0.4</radius><length>0.2</length></cylinder></geometry><material><ambient>1.00.00.01</ambient><diffuse>1.00.00.01</diffuse><specular>1.00.00.01</specular></material></visual><collisionname='collision'><geometry><cylinder><radius>0.4</radius><length>0.2</length></cylinder></geometry></collision></link><framename="caster_frame"attached_to='chassis'><pose>0.80-0.2000</pose></frame><!--caster wheel--><linkname='caster'><poserelative_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><visualname='visual'><geometry><sphere><radius>0.2</radius></sphere></geometry><material><ambient>0.010.01</ambient><diffuse>0.010.01</diffuse><specular>0.010.01</specular></material></visual><collisionname='collision'><geometry><sphere><radius>0.2</radius></sphere></geometry></collision></link><!--connecting these links together using joints--><jointname='left_wheel_joint'type='revolute'><!--continous joint is not supported yet--><poserelative_to='left_wheel'/><parent>chassis</parent><child>left_wheel</child><axis><xyzexpressed_in='__model__'>010</xyz><!--can be defined as any frame or even arbitrary frames--><limit><lower>-1.79769e+308</lower><!--negative infinity--><upper>1.79769e+308</upper><!--positive infinity--></limit></axis></joint><jointname='right_wheel_joint'type='revolute'><poserelative_to='right_wheel'/><parent>chassis</parent><child>right_wheel</child><axis><xyzexpressed_in='__model__'>010</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--><jointname='caster_wheel'type='ball'><parent>chassis</parent><child>caster</child></joint><!--diff drive plugin--><pluginfilename="gz-sim-diff-drive-system"name="gz::sim::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><!-- Moving Left--><pluginfilename="gz-sim-triggered-publisher-system"name="gz::sim::systems::TriggeredPublisher"><inputtype="gz.msgs.Int32"topic="/keyboard/keypress"><matchfield="data">16777234</match></input><outputtype="gz.msgs.Twist"topic="/cmd_vel">linear:{x:0.0},angular:{z:0.5}
</output></plugin><!-- Moving Forward--><pluginfilename="gz-sim-triggered-publisher-system"name="gz::sim::systems::TriggeredPublisher"><inputtype="gz.msgs.Int32"topic="/keyboard/keypress"><matchfield="data">16777235</match></input><outputtype="gz.msgs.Twist"topic="/cmd_vel">linear:{x:0.5},angular:{z:0.0}
</output></plugin><!-- Moving Right--><pluginfilename="gz-sim-triggered-publisher-system"name="gz::sim::systems::TriggeredPublisher"><inputtype="gz.msgs.Int32"topic="/keyboard/keypress"><matchfield="data">16777236</match></input><outputtype="gz.msgs.Twist"topic="/cmd_vel">linear:{x:0.0},angular:{z:-0.5}
</output></plugin><!-- Moving Backward--><pluginfilename="gz-sim-triggered-publisher-system"name="gz::sim::systems::TriggeredPublisher"><inputtype="gz.msgs.Int32"topic="/keyboard/keypress"><matchfield="data">16777237</match></input><outputtype="gz.msgs.Twist"topic="/cmd_vel">linear:{x:-0.5},angular:{z:0.0}
</output></plugin></world></sdf>