Wiki

  Show EOL distros: 

hector_slam: hector_compressed_map_transport | hector_geotiff | hector_imu_attitude_to_tf | hector_map_server | hector_map_tools | hector_mapping | hector_nav_msgs | hector_slam_launch | hector_trajectory_server

Package Summary

hector_mapping is a SLAM approach that can be used without odometry as well as on platforms that exhibit roll/pitch motion (of the sensor, the platform or both). It leverages the high update rate of modern LIDAR systems like the Hokuyo UTM-30LX and provides 2D pose estimates at scan rate of the sensors (40Hz for the UTM-30LX). While the system does not provide explicit loop closing ability, it is sufficiently accurate for many real world scenarios. The system has successfully been used on Unmanned Ground Robots, Unmanned Surface Vehicles, Handheld Mapping Devices and logged data from quadrotor UAVs.

hector_slam: hector_compressed_map_transport | hector_geotiff | hector_geotiff_plugins | hector_imu_attitude_to_tf | hector_map_server | hector_map_tools | hector_mapping | hector_nav_msgs | hector_slam_launch | hector_trajectory_server

Package Summary

hector_mapping is a SLAM approach that can be used without odometry as well as on platforms that exhibit roll/pitch motion (of the sensor, the platform or both). It leverages the high update rate of modern LIDAR systems like the Hokuyo UTM-30LX and provides 2D pose estimates at scan rate of the sensors (40Hz for the UTM-30LX). While the system does not provide explicit loop closing ability, it is sufficiently accurate for many real world scenarios. The system has successfully been used on Unmanned Ground Robots, Unmanned Surface Vehicles, Handheld Mapping Devices and logged data from quadrotor UAVs.

hector_slam: hector_compressed_map_transport | hector_geotiff | hector_geotiff_plugins | hector_imu_attitude_to_tf | hector_map_server | hector_map_tools | hector_mapping | hector_marker_drawing | hector_nav_msgs | hector_slam_launch | hector_trajectory_server

Package Summary

hector_mapping is a SLAM approach that can be used without odometry as well as on platforms that exhibit roll/pitch motion (of the sensor, the platform or both). It leverages the high update rate of modern LIDAR systems like the Hokuyo UTM-30LX and provides 2D pose estimates at scan rate of the sensors (40Hz for the UTM-30LX). While the system does not provide explicit loop closing ability, it is sufficiently accurate for many real world scenarios. The system has successfully been used on Unmanned Ground Robots, Unmanned Surface Vehicles, Handheld Mapping Devices and logged data from quadrotor UAVs.

hector_slam: hector_compressed_map_transport | hector_geotiff | hector_geotiff_plugins | hector_imu_attitude_to_tf | hector_map_server | hector_map_tools | hector_mapping | hector_marker_drawing | hector_nav_msgs | hector_slam_launch | hector_trajectory_server

Package Summary

hector_mapping is a SLAM approach that can be used without odometry as well as on platforms that exhibit roll/pitch motion (of the sensor, the platform or both). It leverages the high update rate of modern LIDAR systems like the Hokuyo UTM-30LX and provides 2D pose estimates at scan rate of the sensors (40Hz for the UTM-30LX). While the system does not provide explicit loop closing ability, it is sufficiently accurate for many real world scenarios. The system has successfully been used on Unmanned Ground Robots, Unmanned Surface Vehicles, Handheld Mapping Devices and logged data from quadrotor UAVs.

hector_slam: hector_compressed_map_transport | hector_geotiff | hector_geotiff_plugins | hector_imu_attitude_to_tf | hector_map_server | hector_map_tools | hector_mapping | hector_marker_drawing | hector_nav_msgs | hector_slam_launch | hector_trajectory_server

Package Summary

hector_mapping is a SLAM approach that can be used without odometry as well as on platforms that exhibit roll/pitch motion (of the sensor, the platform or both). It leverages the high update rate of modern LIDAR systems like the Hokuyo UTM-30LX and provides 2D pose estimates at scan rate of the sensors (40Hz for the UTM-30LX). While the system does not provide explicit loop closing ability, it is sufficiently accurate for many real world scenarios. The system has successfully been used on Unmanned Ground Robots, Unmanned Surface Vehicles, Handheld Mapping Devices and logged data from quadrotor UAVs.

hector_slam: hector_compressed_map_transport | hector_geotiff | hector_geotiff_plugins | hector_imu_attitude_to_tf | hector_map_server | hector_map_tools | hector_mapping | hector_marker_drawing | hector_nav_msgs | hector_slam_launch | hector_trajectory_server

Package Summary

hector_mapping is a SLAM approach that can be used without odometry as well as on platforms that exhibit roll/pitch motion (of the sensor, the platform or both). It leverages the high update rate of modern LIDAR systems like the Hokuyo UTM-30LX and provides 2D pose estimates at scan rate of the sensors (40Hz for the UTM-30LX). While the system does not provide explicit loop closing ability, it is sufficiently accurate for many real world scenarios. The system has successfully been used on Unmanned Ground Robots, Unmanned Surface Vehicles, Handheld Mapping Devices and logged data from quadrotor UAVs.

hector_slam: hector_compressed_map_transport | hector_geotiff | hector_geotiff_plugins | hector_imu_attitude_to_tf | hector_map_server | hector_map_tools | hector_mapping | hector_marker_drawing | hector_nav_msgs | hector_slam_launch | hector_trajectory_server

Package Summary

hector_mapping is a SLAM approach that can be used without odometry as well as on platforms that exhibit roll/pitch motion (of the sensor, the platform or both). It leverages the high update rate of modern LIDAR systems like the Hokuyo UTM-30LX and provides 2D pose estimates at scan rate of the sensors (40Hz for the UTM-30LX). While the system does not provide explicit loop closing ability, it is sufficiently accurate for many real world scenarios. The system has successfully been used on Unmanned Ground Robots, Unmanned Surface Vehicles, Handheld Mapping Devices and logged data from quadrotor UAVs.

hector_slam: hector_compressed_map_transport | hector_geotiff | hector_geotiff_plugins | hector_imu_attitude_to_tf | hector_map_server | hector_map_tools | hector_mapping | hector_marker_drawing | hector_nav_msgs | hector_slam_launch | hector_trajectory_server

Package Summary

hector_mapping is a SLAM approach that can be used without odometry as well as on platforms that exhibit roll/pitch motion (of the sensor, the platform or both). It leverages the high update rate of modern LIDAR systems like the Hokuyo UTM-30LX and provides 2D pose estimates at scan rate of the sensors (40Hz for the UTM-30LX). While the system does not provide explicit loop closing ability, it is sufficiently accurate for many real world scenarios. The system has successfully been used on Unmanned Ground Robots, Unmanned Surface Vehicles, Handheld Mapping Devices and logged data from quadrotor UAVs.

Package Summary

hector_mapping is a SLAM approach that can be used without odometry as well as on platforms that exhibit roll/pitch motion (of the sensor, the platform or both). It leverages the high update rate of modern LIDAR systems like the Hokuyo UTM-30LX and provides 2D pose estimates at scan rate of the sensors (40Hz for the UTM-30LX). While the system does not provide explicit loop closing ability, it is sufficiently accurate for many real world scenarios. The system has successfully been used on Unmanned Ground Robots, Unmanned Surface Vehicles, Handheld Mapping Devices and logged data from quadrotor UAVs.

  • Maintainer status: maintained
  • Maintainer: Johannes Meyer <meyer AT fsr.tu-darmstadt DOT de>
  • Author: Stefan Kohlbrecher <kohlbrecher AT sim.tu-darmstadt DOT de>
  • License: BSD

Overview

An example video can be seen here:

Further video examples are available in this playlist: http://www.youtube.com/playlist?list=PL0E462904E5D35E29

Details can also be found in this paper:

@INPROCEEDINGS{KohlbrecherMeyerStrykKlingaufFlexibleSlamSystem2011,
  author = {S. Kohlbrecher and J. Meyer and O. von Stryk and U. Klingauf},
  title = {A Flexible and Scalable SLAM System with Full 3D Motion Estimation},
  year = {2011},
  month = {November},
  booktitle = {Proc. IEEE International Symposium on Safety, Security and Rescue Robotics (SSRR)},
  organization = {IEEE},
}

available here .

Hardware Requirements

To use hector_mapping, you need a source of sensor_msgs/LaserScan data (for example a Hokuyo UTM-30LX LIDAR or bagfiles). The node uses tf for transformation of scan data, so the LIDAR does not have to be fixed related to the specified base frame. Odometry data is not needed.

ROS API

hector_mapping

hector_mapping is a node for LIDAR based SLAM with no odometry and low computational resources. For simplicity, the ROS API detailed below provides information about the commonly used options from a user perspective, but not all options that are available for debugging purposes.

Subscribed Topics

scan (sensor_msgs/LaserScan) syscommand (std_msgs/String)

Published Topics

map_metadata (nav_msgs/MapMetaData) map (nav_msgs/OccupancyGrid) slam_out_pose (geometry_msgs/PoseStamped) poseupdate (geometry_msgs/PoseWithCovarianceStamped)

Services

dynamic_map (nav_msgs/GetMap) reset_map (std_srvs/Trigger) pause_mapping (std_srvs/SetBool) restart_mapping_with_new_pose (hector_mapping/ResetMapping)

Parameters

~base_frame (string, default: base_link) ~map_frame (string, default: map_link) ~odom_frame (string, default: odom) ~map_resolution (double, default: 0.025) ~map_size (int, default: 1024) ~map_start_x (double, default: 0.5) ~map_start_y (double, default: 0.5) ~map_update_distance_thresh (double, default: 0.4) ~map_update_angle_thresh (double, default: 0.9) ~map_pub_period (double, default: 2.0) ~map_multi_res_levels (int, default: 3) ~update_factor_free (double, default: 0.4) ~update_factor_occupied (double, default: 0.9) ~laser_min_dist (double, default: 0.4) ~laser_max_dist (double, default: 30.0) ~laser_z_min_value (double, default: -1.0) ~laser_z_max_value (double, default: 1.0) ~pub_map_odom_transform (bool, default: true) ~output_timing (bool, default: false) ~scan_subscriber_queue_size (int, default: 5) ~pub_map_scanmatch_transform (bool, default: true) ~tf_map_scanmatch_transform_frame_name (string, default: scanmatcher_frame)

Required tf Transforms

<the frame attached to incoming scans>base_frame

Provided tf Transforms

mapodom

Wiki: hector_mapping (last edited 2021-03-24 15:28:26 by Marcelino Almeida)