Show EOL distros:
Package Summary
A wrapper around Polar Scan Matcher by Albert Diosi and Lindsay Kleeman, used for laser scan registration.
- Author: Ivan Dryanovski
- License: GPL
- Repository: ccny-ros-pkg
- Source: git http://robotics.ccny.cuny.edu/git/ccny-ros-pkg/scan_tools.git
Package Summary
A wrapper around Polar Scan Matcher by Albert Diosi and Lindsay Kleeman, used for laser scan registration.
- Author: Ivan Dryanovski
- License: GPL
- Repository: ccny-ros-pkg
- Source: git https://github.com/ccny-ros-pkg/scan_tools.git
Package Summary
A wrapper around Polar Scan Matcher by Albert Diosi and Lindsay Kleeman, used for laser scan registration.
- Maintainer status: maintained
- Maintainer: Ivan Dryanovski <ccnyroboticslab AT gmail DOT com>, Carlos <cjaramillo AT gc.cuny DOT edu>
- Author: Ivan Dryanovski
- License: GPL
- Source: git https://github.com/ccny-ros-pkg/scan_tools.git (branch: indigo)
Package Summary
A wrapper around Polar Scan Matcher by Albert Diosi and Lindsay Kleeman, used for laser scan registration.
- Maintainer status: maintained
- Maintainer: Ivan Dryanovski <ccnyroboticslab AT gmail DOT com>, Carlos <cjaramillo AT gc.cuny DOT edu>
- Author: Ivan Dryanovski
- License: GPL
- Source: git https://github.com/ccny-ros-pkg/scan_tools.git (branch: indigo)
Package Summary
A wrapper around Polar Scan Matcher by Albert Diosi and Lindsay Kleeman, used for laser scan registration.
- Maintainer status: maintained
- Maintainer: Ivan Dryanovski <ccnyroboticslab AT gmail DOT com>, Carlos <cjaramillo AT gc.cuny DOT edu>
- Author: Ivan Dryanovski
- License: GPL
- Source: git https://github.com/ccny-ros-pkg/scan_tools.git (branch: indigo)
Package Summary
A wrapper around Polar Scan Matcher by Albert Diosi and Lindsay Kleeman, used for laser scan registration.
- Maintainer status: unmaintained
- Maintainer: Ivan Dryanovski <ccnyroboticslab AT gmail DOT com>, Carlos <cjaramillo AT gc.cuny DOT edu>
- Author: Ivan Dryanovski
- License: GPL
- Source: git https://github.com/ccny-ros-pkg/scan_tools.git (branch: ros1)
Package Summary
A wrapper around Polar Scan Matcher by Albert Diosi and Lindsay Kleeman, used for laser scan registration.
- Maintainer status: unmaintained
- Maintainer: Ivan Dryanovski <ccnyroboticslab AT gmail DOT com>, Carlos <cjaramillo AT gc.cuny DOT edu>
- Author: Ivan Dryanovski
- License: GPL
- Source: git https://github.com/CCNYRoboticsLab/scan_tools.git (branch: ros1)
Contents
Details
The polar_scan_matcher package is a wrapper around Polar Scan Matcher [1], courtesy of:
Albert Diosi and Lindsay Kleeman
Intelligent Robotics Research Centre (IRRC)
Monash University
http://www.irrc.monash.edu.au/adiosi/downloads.html
The package allows to scan match between consecutive sensor_msgs/LaserScan messages, and publish the estimated position of the laser as a geometry_msgs/Pose2D or a tf transform.
The package is intended to be used without any odometry estimation provided by other sensors. Thus, it can serve as a stand-alone odometry estimator.
An estimation for theta can optionally be provided to improve accuracy, in the form of a sensor_msgs/Imu. This message would typically be published by an IMU or other angular rate sensor.
Alternatively, an estimation for x, y, and theta can optionally be provided to improve accuracy, in the form of a tf transform. This transform would typically be published by an odometry system. This has not yet been tested.
Example
You can run the polar_scan_matcher on a pre-recorded bag file that comes with the package. First, make sure you have the scan_tools stack downloaded and installed by following the instructions here.
Next, make sure you have the necessary tools installed:
1 rosmake rviz rosbag tf
Finally, run the demo:
1 roslaunch polar_scan_matcher demo.launch
You should see a result similar to the video below. The video shows PSM tracking the position of a Hokuyo laser as it is being carried freely around a room. The pose is determined entirely by the scan matcher - no additional odometry is provided.
Nodes
psm_node
The psm_node takes in sensor_msgs/LaserScan messages, performs scan registration, and outputs an estimate for the displacement of the robot.Subscribed Topics
scan (sensor_msgs/LaserScan)- Scans from a laser range-finder
- Imu messages, used for theta estimation. Only used if odometry_type is set to imu.
Published Topics
pose2D (geometry_msgs/Pose2D)- The pose of the base frame, in some fixed (world) frame.
Parameters
~world_frame (string, default: "world")- the fixed frame
- the base frame of the robot
- whether to publish scan matcher's estimation for the position of the base frame in the world frame as a transform. Disable this if some other node is already publishing an odometric estimation.
- whether to publish scan matcher's estimation for the position of the base frame in the world frame as a geometry_msgs/Pose2D
- If "none", the scan matcher will not use any estimate for the displacement between scans. If "imu", the matcher will use as an estimate the yaw value of sensor_msgs/Imu messages published on a topic called "imu". If "tf", the matcher will use as an estimate the x, y, and yaw value of a tf transform between the world and base frames.
- the minimum valid points required to perform a scan match
- the window in which to search for a match for the rotation. The units are number of laser scan beams.
- the maximum distance, in meters, for correlating two points.
- the maximum number of algorithm iterations
- the stop condition, in meters, for the variance of the error
Required tf Transforms
base_link → laser- the pose of the laser in the base frame. Only needed when use_odometry is enabled.
Provided tf Transforms
world → base_link- the pose of the robot base in the world frame. Only provided when publish_tf is enabled.
References
[1] A. Diosi and L. Kleeman, "Laser Scan Matching in Polar Coordinates with Application to SLAM " Proceedings of 2005 IEEE/RSJ International Conference on Intelligent Robots and Systems, August, 2005, Edmonton, Canada
Bug Reports & Feature Requests
We appreciate the time and effort spent submitting bug reports.
Please use our Trac to report bugs or request features.