This page provides a detailed guide on integrating a robot odometry system with Nav2 (Navigation Stack for ROS). It explains the concept of odometry, which involves generating pose and velocity estimates based on various sources like wheel encoders, visual odometry, and IMU data. The odometry information is combined using the robot_localization
package to create an odom
frame, which is then transformed to the base_footprint
frame. The page also covers setting up robot odometry for differential drive and Ackermann steering robots using Gazebo plugins. Additionally, it describes how to incorporate an IMU for accurate odometry through sensor fusion. Lastly, it explains the use of an Extended Kalman Filter (EKF) with the robot_localization
package to fuse wheel encoder and IMU data for more accurate and smoother odometry. The tutorial includes YAML configuration files and launch files for implementing these functionalities in ROS.
To add a LIDAR sensor to your robot URDF, you must first add a link representing the sensor. The following URDF code describes a Velodyne Lidar sensor to corresponding with the Velodyne .dae
file.
<link name="lidar_link">
<inertial>
<origin xyz="0 0 -0.025" rpy="0 0 0" />
<mass value="1.0" />
<inertia ixx="${1.0* (3.0 * 0.10 * 0.10 + 0.20 * .20) / 12.0}"
ixy="0.0" ixz="0.0"
iyy="${1.0 * (3.0 * 0.10 * 0.10 + 0.20 * 0.20) / 12.0}"
iyz="0.0"
izz="${1.0 * (0.10 * 0.10) / 2.0}" />
</inertial>
<collision>
<origin xyz="0 0 -0.025" rpy="0 0 0" />
<geometry>
<mesh
filename="package://hunter_se_description/models/meshes/Velodyne.dae" />
</geometry>
</collision>
<visual>
<origin xyz="0 0 -0.025" rpy="0 0 0" />
<geometry>
<mesh
filename="package://hunter_se_description/models/meshes/Velodyne.dae" />
</geometry>
</visual>
</link>
Add this Velodyne.dae
to your hunter_se_description/models/meshes
folder to use the visual model.
Now that the visual component of the link has been created, a gazebo
reference to that link has to be set such that the sensor will publish information about the gazebo
environment.
Within your robot urdf
add a gazebo reference
to initialize the lidar. Add the following code to your robot sensors urdf
:
<gazebo reference="lidar_link">
<sensor name="velodyne" type="ray">
<always_on>true</always_on>
<visualize>false</visualize>
<pose>0.0 0 0.0 0 0 0</pose>
<update_rate>15</update_rate>
<ray>
<scan>
<horizontal>
<samples>360</samples>
<resolution>1.00</resolution>
<min_angle>0.000000</min_angle>
<max_angle>6.280000</max_angle>
</horizontal>
</scan>
<range>
<min>0.120000</min>
<max>3.5</max>
<resolution>0.015</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name="velodyne_laserscan" filename="libgazebo_ros_ray_sensor.so">
<ros>
<remapping>~/out:=scan</remapping>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
<frame_name>${name}_lidar_link</frame_name>
</plugin>
</sensor>
</gazebo>
Lets look at what that gazebo
reference block means. Firstly, we must initialize which robot link is going to be used as the sensor. That is done using the sensor
tag. The name of the sensor, as well as the sensor type are given within this tag. Some initializing parameters are also set regarding visualizing, update rate, and initial position.
<sensor name="velodyne" type="ray">
<always_on>true</always_on>
<visualize>false</visualize>
<pose>0.0 0 0.0 0 0 0</pose>
<update_rate>15</update_rate>
Next, the sensor configurations are set so that the LIDAR ray sensor behaves like the physical unit. The resolution, range, samples, and sensor noise are all set within the ray
tags.
<ray>
<scan>
<horizontal>
<samples>360</samples>
<resolution>1.00</resolution>
<min_angle>0.000000</min_angle>
<max_angle>6.280000</max_angle>
</horizontal>
</scan>
<range>
<min>0.120000</min>
<max>3.5</max>
<resolution>0.015</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
Next, the gazebo
plugin used to generate the LIDAR topics is called. These are called within plugin
tags (within the sensor
tag). ROS parameters such as topic remapping, output types, and the frame name are all set within this plugin
tag.
<plugin name="velodyne_laserscan" filename="libgazebo_ros_ray_sensor.so">
<ros>
<remapping>~/out:=scan</remapping>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
<frame_name>lidar_link</frame_name>
</plugin>
Now your LIDAR sensor will work and publish information on the /scan
topic.
Previous Page: Adding Gazebo Plugins to a URDF
Next Page: Depth Camera