This guide details the steps to configure and use Hector SLAM with a Roboclaw-based ROS 1 robot. We’ll cover LIDAR integration, transform configuration, and how to set RViz for successful mapping and navigation.
Ensure the following are set up on your system:
- ROS Installed: ROS Melodic or a compatible version is installed.
- Workspace Prepared: A catkin workspace (e.g.,
~/armpi_pro
) is created, built, and sourced.
- Hector SLAM Package:
- Installed and located in your workspace under
src/hector_slam
.
- Ensure
hector_mapping
and hector_slam_launch
are available.
- LIDAR Sensor:
- Configured and publishing scan data to
/scan
.
- Roboclaw Node:
- Operational, publishing odometry to
/odom
.
Open a terminal and start the ROS core:
This is required for all other nodes to communicate.
To enable LIDAR data for mapping, launch the LIDAR node in a new terminal:
roslaunch ldlidar_stl_ros ld19.launch
This ensures the LIDAR sensor is active and publishing data to the /scan
topic, which is necessary for Hector SLAM to create a map.
In your workspace, navigate to the Hector SLAM launch folder:
cd ~/armpi_pro/src/hector_slam/hector_slam_launch/launch
Use the tutorial.launch
file as a base for running Hector SLAM. Modify the following parameters in the launch file to match your setup:
<launch>
<!-- Hector Mapping Node -->
<node pkg="hector_mapping" type="hector_mapping" name="hector_mapping" output="screen">
<param name="pub_map_odom_transform" value="true"/>
<param name="map_frame" value="map"/>
<param name="base_frame" value="base_link"/>
<param name="odom_frame" value="odom"/>
<remap from="scan" to="/scan"/> <!-- Your LIDAR topic -->
<remap from="odom" to="/odom"/> <!-- Your odometry topic -->
</node>
<!-- Static Transform Publisher -->
<node pkg="tf2_ros" type="static_transform_publisher" name="laser_to_base_link"
args="0 0 0.2 0 0 0 base_link laser_link"/>
<!-- RViz for Visualization -->
<node pkg="rviz" type="rviz" name="rviz" args="-d $(find hector_slam_launch)/rviz_cfg/mapping.rviz" />
</launch>
Run the newly created launch file above using:
roslaunch hector_slam_launch mapping_with_odom.launch
To visualize the mapping process:
-
Start RViz:
-
Set the Fixed Frame to scanmatcher_frame
:
- Navigate to
Global Options
in RViz.
-
Set Fixed Frame
to scanmatcher_frame
.
-
Add relevant displays:
- Map: Subscribe to
/map
for live updates.
- LaserScan: Subscribe to
/scan
to visualize LIDAR data.
- TF: Check the frame hierarchy and transformations.
Start the Roboclaw node to handle motor control and odometry:
roslaunch roboclaw_node roboclaw.launch
This node should publish odometry data to the /odom
topic, which Hector SLAM uses.
Now that the mapping and motor control nodes are active:
- Drive the rover manually or programmatically using the following script:
#!/usr/bin/env python2
# -*- coding: utf-8 -*-
"""
Example: Use Pygame to read an Xbox controller and RoboClaw on ROS Melodic (Python 2).
No f-strings; uses .format().
Make sure:
1) roscore is running (for rospy logs).
2) SDL_VIDEODRIVER=dummy is set if headless: export SDL_VIDEODRIVER=dummy
3) RoboClaw is on /dev/ttyACM0 (or change param).
"""
import sys
import rospy
import pygame
import time
# For TF in Melodic (Python 2)
import tf
import tf.transformations as tft
# RoboClaw library (python2-compatible)
from roboclaw import Roboclaw
class XboxRoboclawDebugPy2(object):
def __init__(self):
# 1) ROS init
rospy.init_node("xbox_teleop_debug_py2", anonymous=True)
rospy.loginfo("Starting xbox_teleop_debug_py2 node...")
# 2) RoboClaw Setup
self.port_name = rospy.get_param("~port", "/dev/ttyACM0")
self.baud_rate = rospy.get_param("~baud", 115200)
self.address = rospy.get_param("~address", 0x80) # decimal 128
rospy.loginfo("Attempting to open RoboClaw on {0} at {1} baud, address=0x{2:X}".format(
self.port_name, self.baud_rate, self.address))
self.rc = Roboclaw(self.port_name, self.baud_rate)
if not self.rc.Open():
rospy.logerr("Failed to open RoboClaw on {0}. Exiting.".format(self.port_name))
sys.exit(1)
rospy.loginfo("RoboClaw opened successfully on {0}.".format(self.port_name))
# 3) Initialize Pygame
pygame.init()
pygame.joystick.init()
joystick_count = pygame.joystick.get_count()
rospy.loginfo("Detected {0} joystick(s).".format(joystick_count))
if joystick_count == 0:
rospy.logerr("No joystick detected. Exiting.")
sys.exit(1)
self.joystick = pygame.joystick.Joystick(0)
self.joystick.init()
rospy.loginfo("Joystick: {0}".format(self.joystick.get_name()))
# 4) Speed config
self.max_speed_cmd = 15.0 # if 127 is full speed, 20 is slower
self.deadzone = 0.1
rospy.loginfo("max_speed_cmd={0}, deadzone={1}".format(self.max_speed_cmd, self.deadzone))
# Rate
self.loop_rate = rospy.Rate(20) # 20 Hz
# On shutdown => stop motors
rospy.on_shutdown(self.stop_motors)
rospy.loginfo("Initialization complete. Ready to run...")
def stop_motors(self):
rospy.loginfo("Stopping motors.")
self.rc.ForwardM1(self.address, 0)
self.rc.ForwardM2(self.address, 0)
def run(self):
loop_counter = 0
while not rospy.is_shutdown():
loop_counter += 1
# Just for debugging
rospy.logdebug("Main loop iteration={0}".format(loop_counter))
pygame.event.pump()
# Example: left stick vertical = axis 1, right stick horizontal = axis 3
forward_axis = -self.joystick.get_axis(1)
turn_axis = self.joystick.get_axis(3)
# Debug prints
rospy.logdebug("Raw axes => forward_axis={0:.2f}, turn_axis={1:.2f}".format(
forward_axis, turn_axis))
# Deadzone
if abs(forward_axis) < self.deadzone:
forward_axis = 0.0
if abs(turn_axis) < self.deadzone:
turn_axis = 0.0
# Skid-steer mixing
left_val = forward_axis - turn_axis
right_val = forward_axis + turn_axis
# clamp [-1..+1]
left_val = max(-1.0, min(1.0, left_val))
right_val = max(-1.0, min(1.0, right_val))
# Convert to RoboClaw speed
left_speed, left_dir = self.convert_speed(left_val)
right_speed, right_dir = self.convert_speed(right_val)
rospy.logdebug("Mixed => L={0:.2f}, R={1:.2f} => speeds {2} ({3}), {4} ({5})".format(
left_val, right_val, left_speed, left_dir, right_speed, right_dir))
# Send to motors
if left_dir == "forward":
self.rc.ForwardM1(self.address, left_speed)
else:
self.rc.BackwardM1(self.address, left_speed)
if right_dir == "forward":
self.rc.ForwardM2(self.address, right_speed)
else:
self.rc.BackwardM2(self.address, right_speed)
self.loop_rate.sleep()
self.stop_motors()
pygame.quit()
def convert_speed(self, val):
"""
Convert [-1..+1] => (0..max_speed_cmd, direction).
"""
if val >= 0:
return (int(val * self.max_speed_cmd), "forward")
else:
return (int(abs(val) * self.max_speed_cmd), "backward")
def main():
try:
node = XboxRoboclawDebugPy2()
node.run()
except rospy.ROSInterruptException:
pass
finally:
rospy.loginfo("Exiting python2 xbox teleop script.")
if __name__ == "__main__":
main()
- Watch the map being built in RViz.
- Ensure the rover avoids obstacles and updates the map in real-time.
Here’s a summary of the adjustments we made to configure Hector SLAM:
- Set Fixed Frame in RViz to
scanmatcher_frame
.
- Modified the Hector SLAM launch file to include:
pub_map_odom_transform
set to true
.
- Correct frame names (
map
, odom
, base_link
).
- Verified LIDAR publishing to
/scan
using ld19.launch
.
- Ensured odometry data was published to
/odom
by the Roboclaw node.
If you see errors like "Lookup would require extrapolation into the future," check the following:
- Ensure the system clocks are synchronized using ntp
or chrony
.
- Verify all topics (/scan
, /odom
) have valid and synchronized timestamps.
Run:
If no data appears, ensure the LIDAR launch file is correctly configured and the sensor is operational.
By following these steps, you’ve successfully set up Hector SLAM on a Roboclaw-based ROS 1 rover. With LIDAR and odometry data, your rover can build a 2D map of its environment, enabling autonomous navigation and enhanced spatial awareness.
Feel free to experiment with SLAM parameters and refine your rover’s capabilities for your specific use case.