Only released in EOL distros:
Package Summary
Localizing jockey from LaserScan and absolute heading. Implements a localizing jockey from a LaserScan and absolute heading. The associated descriptors are sensor_msgs/LaserScan[] and lama_msgs/Crossing.
- Maintainer status: developed
- Maintainer: Gaël Ecorchard <gael.ecorchard AT ciirc.cvut DOT cz>
- Author: Gaël Ecorchard <gael.ecorchard AT ciirc.cvut DOT cz>
- License: BSD
- Bug / feature tracker: https://github.com/lama-imr/lama_laser/issues
- Source: git https://github.com/lama-imr/lama_laser.git (branch: indigo-devel)
Contents
Overview
The lj_laser_heading package implements a localizing jockey that computes place dissimilarities based on a sensor_msgs/LaserScan and absolute heading. The behavior and properties are similar to those of the lj_laser jockey. The heading is given either as geometry_msgs/Pose or nav_msgs/Odometry.
The role of this jockey is to get the dissimilarity of the sensor_msgs/LaserScan descriptor of all vertices with the current place profile (represented by a sensor_msgs/LaserScan). The action is done when the dissimilarities are computed. Implemented actions:
GET_VERTEX_DESCRIPTOR: return the ids of the sensor_msgs/LaserScan descriptor and the computed lama_msgs/Crossing descriptor
GET_SIMILARITY: return the dissimilarity based on sensor_msgs/LaserScan
Usage
ROS API
Interaction with the map (created by this jockey)
[Getter][/][Setter] |
message type |
interface default name |
Getter/Setter |
VectorLaserScan |
jockey_name + "_laser" |
Setter |
jockey_name + "_crossing" |
Subscribed Topics
~<name>/base_scan (sensor_msgs/LaserScan)- 360-degree laser-scan
Services
~<name>/dissimilarity_server (polygon_matcher/PolygonDissimilarity)- used to compare all known places (as polygons) with the current place.
Parameters
~<name>/laser_interface_name (String, default: jockey_name + "_laser")- Name of the map interface for laser-scans.
- Name of the map interface for crossings.
- Name of the dissimilarity server.