ND2 - Project 2 - localization - files
Worlds Files (define environment)
A world is a collection of models such as your robot, cup, ground and sky.
<?xml version="1.0" ?>
<sdf version="1.4">
<world name="default">
<!-- Ground plane -->
<include>
<uri>model://ground_plane</uri>
</include>
<!-- Light source -->
<include>
<uri>model://sun</uri>
</include>
<!-- World camera -->
<gui fullscreen='0'>
<camera name='world_camera'>
<pose>4.927360 -4.376610 3.740080 0.000000 0.275643 2.356190</pose>
<view_controller>orbit</view_controller>
</camera>
</gui>
</world>
</sdf>
Unified Robot Description Format (URDF) (define robot)
URDF can only describe a robot with rigid links connected by joints, not flexible links or parallel linkage.
Divided into 2 files (xacro / gazebo)
udacity_bot.xacro (robot specific information like links, joints, actuators, etc.)
visual + collision + inertial
<?xml version='1.0'?>
<robot name="udacity_bot" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find udacity_bot)/urdf/udacity_bot.gazebo" />
<!-- footprint LINK -->
<link name="robot_footprint"></link>
<!-- footprint - chassis JOINT -->
<joint name="robot_footprint_joint" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="robot_footprint"/>
<child link="chassis" />
</joint>
<!-- chassis LINK -->
<link name='chassis'>
<pose>0 0 0.1 0 0 0</pose>
<inertial>
<mass value="15.0"/>
<origin xyz="0.0 0 0" rpy=" 0 0 0"/>
<inertia
ixx="0.1" ixy="0" ixz="0"
iyy="0.1" iyz="0"
izz="0.1"
/>
</inertial>
<collision name='collision'>
<origin xyz="0 0 0" rpy=" 0 0 0"/>
<geometry>
<box size=".4 .2 .1"/>
</geometry>
</collision>
<visual name='chassis_visual'>
<origin xyz="0 0 0" rpy=" 0 0 0"/>
<geometry>
<box size=".4 .2 .1"/>
</geometry>
</visual>
<collision name='back_caster_collision'>
<origin xyz="-0.15 0 -0.05" rpy=" 0 0 0"/>
<geometry>
<sphere radius="0.05"/>
</geometry>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<slip1>1.0</slip1>
<slip2>1.0</slip2>
</ode>
</friction>
</surface>
</collision>
<visual name='back_caster_visual'>
<origin xyz="-0.15 0 -0.05" rpy=" 0 0 0"/>
<geometry>
<sphere radius="0.05"/>
</geometry>
</visual>
<collision name='front_caster_collision'>
<origin xyz="0.15 0 -0.05" rpy=" 0 0 0"/>
<geometry>
<sphere radius="0.05"/>
</geometry>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<slip1>1.0</slip1>
<slip2>1.0</slip2>
</ode>
</friction>
</surface>
</collision>
<visual name='front_caster_visual'>
<origin xyz="0.15 0 -0.05" rpy=" 0 0 0"/>
<geometry>
<sphere radius="0.05"/>
</geometry>
</visual>
</link>
<!-- right wheel LINK -->
<link name='right_wheel'>
<inertial>
<mass value="5.0"/>
<origin xyz="0 0 0" rpy=" 0 1.5707 1.5707"/>
<inertia
ixx="0.1" ixy="0" ixz="0"
iyy="0.1" iyz="0"
izz="0.1"
/>
</inertial>
<collision>
<origin xyz="0 0 0" rpy=" 0 1.5707 1.5707"/>
<geometry>
<cylinder length="0.05" radius="0.1"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy=" 0 1.5707 1.5707"/>
<geometry>
<cylinder length="0.05" radius="0.1"/>
</geometry>
</visual>
</link>
<!-- right wheel - chassis JOINT -->
<joint type="continuous" name="right_wheel_hinge">
<origin xyz="0 0.15 0" rpy="0 0 0"/>
<child link="right_wheel"/>
<parent link="chassis"/>
<axis xyz="0 1 0" rpy="0 0 0"/>
<limit effort="10000" velocity="1000"/>
<joint_properties damping="1.0" friction="1.0"/>
</joint>
<!-- left wheel - LINK -->
<link name='left_wheel'>
<inertial>
<mass value="5.0"/>
<origin xyz="0 0 0" rpy=" 0 1.5707 1.5707"/>
<inertia
ixx="0.1" ixy="0" ixz="0"
iyy="0.1" iyz="0"
izz="0.1"
/>
</inertial>
<collision>
<origin xyz="0 0 0" rpy=" 0 1.5707 1.5707"/>
<geometry>
<cylinder length="0.05" radius="0.1"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy=" 0 1.5707 1.5707"/>
<geometry>
<cylinder length="0.05" radius="0.1"/>
</geometry>
</visual>
</link>
<!-- left wheel - JOINT -->
<joint type="continuous" name="left_wheel_hinge">
<origin xyz="0 -0.15 0" rpy="0 0 0"/>
<child link="left_wheel"/>
<parent link="chassis"/>
<axis xyz="0 1 0" rpy="0 0 0"/>
<limit effort="10000" velocity="1000"/>
<joint_properties damping="1.0" friction="1.0"/>
</joint>
<!-- camera - LINK -->
<link name='camera'>
<inertial>
<mass value="0.1"/>
<origin xyz="0 0 0" rpy=" 0 0 0"/>
<inertia
ixx="1e-6" ixy="0" ixz="0"
iyy="1e-6" iyz="0"
izz="1e-6"
/>
</inertial>
<collision name='camera_collision'>
<origin xyz="0 0 0" rpy=" 0 0 0"/>
<geometry>
<box size="0.05 0.05 0.05" />
</geometry>
</collision>
<visual name='camera_visual'>
<origin xyz="0 0 0" rpy=" 0 0 0"/>
<geometry>
<box size="0.05 0.05 0.05" />
</geometry>
</visual>
</link>
<!-- camera - chassis JOINT -->
<joint type="fixed" name="camera_joint">
<origin xyz="0.2 0 0" rpy="0 0 0"/>
<child link="camera"/>
<parent link="chassis"/>
</joint>
<!-- laser rangefinder - LINK -->
<link name='hokuyo'>
<inertial>
<mass value="0.1"/>
<origin xyz="0 0 0" rpy=" 0 0 0"/>
<inertia
ixx="1e-6" ixy="0" ixz="0"
iyy="1e-6" iyz="0"
izz="1e-6"
/>
</inertial>
<collision name='hokuyo_collision'>
<origin xyz="0 0 0" rpy=" 0 0 0"/>
<geometry>
<box size="0.1 0.1 0.1" />
</geometry>
</collision>
<visual name='hokuyo_visual'>
<origin xyz="0 0 0" rpy=" 0 0 0"/>
<geometry>
<mesh filename="package://udacity_bot/meshes/hokuyo.dae"/>
</geometry>
</visual>
</link>
<!-- laser rangefinder - chassis JOINT -->
<joint type="fixed" name="hokuyo_joint">
<origin xyz="0.15 0 0.1" rpy="0 0 0"/>
<child link="hokuyo"/>
<parent link="chassis"/>
</joint>
</robot>
udacity_bot.gazebo (gazebo specific info like robot material, frictional constants, and plugins to control the robot in gazebo)
<?xml version="1.0"?>
<robot>
<!-- wheels control plugin -->
<gazebo>
<plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
<legacyMode>false</legacyMode>
<alwaysOn>true</alwaysOn>
<updateRate>10</updateRate>
<leftJoint>left_wheel_hinge</leftJoint>
<rightJoint>right_wheel_hinge</rightJoint>
<wheelSeparation>0.4</wheelSeparation>
<wheelDiameter>0.2</wheelDiameter>
<torque>10</torque>
<commandTopic>cmd_vel</commandTopic>
<odometryTopic>odom</odometryTopic>
<odometryFrame>odom</odometryFrame>
<robotBaseFrame>robot_footprint</robotBaseFrame>
</plugin>
</gazebo>
<!-- right wheel -->
<gazebo reference="right_wheel">
<material>Gazebo/Green</material>
</gazebo>
<!-- left wheel -->
<gazebo reference="left_wheel">
<material>Gazebo/Green</material>
</gazebo>
<!-- chassis -->
<gazebo reference="chassis">
<material>Gazebo/Blue</material>
</gazebo>
<!-- camera -->
<gazebo reference="camera">
<material>Gazebo/Red</material>
<sensor type="camera" name="camera1">
<update_rate>30.0</update_rate>
<camera name="head">
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>800</width>
<height>800</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
</camera>
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
<cameraName>udacity_bot/camera1</cameraName>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>camera</frameName>
<hackBaseline>0.07</hackBaseline>
<distortionK1>0.0</distortionK1>
<distortionK2>0.0</distortionK2>
<distortionK3>0.0</distortionK3>
<distortionT1>0.0</distortionT1>
<distortionT2>0.0</distortionT2>
</plugin>
</sensor>
</gazebo>
<!-- hokuyo -->
<gazebo reference="hokuyo">
<sensor type="ray" name="head_hokuyo_sensor">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>40</update_rate>
<ray>
<scan>
<horizontal>
<samples>720</samples>
<resolution>1</resolution>
<min_angle>-1.570796</min_angle>
<max_angle>1.570796</max_angle>
</horizontal>
</scan>
<range>
<min>0.10</min>
<max>30.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<!-- Noise parameters based on published spec for Hokuyo laser
achieving "+-30mm" accuracy at range < 10m. A mean of 0.0m and
stddev of 0.01m will put 99.7% of samples within 0.03m of the true
reading. -->
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_laser.so">
<topicName>/udacity_bot/laser/scan</topicName>
<frameName>hokuyo</frameName>
</plugin>
</sensor>
</gazebo>
</robot>
A link contains [1]visual [2]inertial [3]collision
Launch Files
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<!--define args-->
<arg name="world" default="empty"/>
<arg name="paused" default="false"/>
<arg name="use_sim_time" default="true"/>
<arg name="gui" default="true"/>
<arg name="headless" default="false"/>
<arg name="debug" default="false"/>
<!--include robot launch files-->
<include file="$(find udacity_bot)/launch/robot_description.launch"/>
<!--include launch files from gazebo-->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(find udacity_bot)/worlds/udacity.world"/>
<arg name="paused" value="$(arg paused)"/>
<arg name="use_sim_time" value="$(arg use_sim_time)"/>
<arg name="gui" value="$(arg gui)"/>
<arg name="headless" value="$(arg headless)"/>
<arg name="debug" value="$(arg debug)"/>
</include>
<!--spawn a robot node in gazebo world-->
<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen" args="-urdf -param robot_description -model udacity_bot"/>
</launch>
more about gazebo empty_world.launch
Adaptive Monte Carlo Localization (AMCL) dynamically adjusts the number of particles over a period of time
Last updated
Was this helpful?