Only released in EOL distros:  

hector_worldmodel: hector_object_tracker | hector_worldmodel_geotiff_plugins | object_tracker | worldmodel_msgs

Package Summary

hector_object_tracker is the core package of hector_worldmodel. It listens to percept message from detectors (e.g. heat signatures of persons or recognitions of other objects of interest in the scene) and fuses all information to a single worldmodel state. Objects will be tracked over time and their states can be influenced by a couple of services. The percept to object association problem is solved either automatically based on the Mahalanobis distance, or a unique object_id can be given in the percept message. If a hector_nav_msgs/GetDistanceToObstacle service is available, the object_tracker can optionally deduce the depth of objects in the scene by projection to the nearest obstacle (wall).

hector_worldmodel: hector_object_tracker | hector_worldmodel_geotiff_plugins | hector_worldmodel_msgs | object_tracker

Package Summary

hector_object_tracker is the core package of hector_worldmodel. It listens to percept message from detectors (e.g. heat signatures of persons or recognitions of other objects of interest in the scene) and fuses all information to a single worldmodel state. Objects will be tracked over time and their states can be influenced by a couple of services. The percept to object association problem is solved either automatically based on the Mahalanobis distance, or a unique object_id can be given in the percept message. If a hector_nav_msgs/GetDistanceToObstacle service is available, the object_tracker can optionally deduce the depth of objects in the scene by projection to the nearest obstacle (wall).

hector_worldmodel: hector_object_tracker | hector_worldmodel_geotiff_plugins | hector_worldmodel_msgs

Package Summary

hector_object_tracker is the core package of hector_worldmodel. It listens to percept message from detectors (e.g. heat signatures of persons or recognitions of other objects of interest in the scene) and fuses all information to a single worldmodel state. Objects will be tracked over time and their states can be influenced by a couple of services. The percept to object association problem is solved either automatically based on the Mahalanobis distance, or a unique object_id can be given in the percept message. If a hector_nav_msgs/GetDistanceToObstacle service is available, the object_tracker can optionally deduce the depth of objects in the scene by projection to the nearest obstacle (wall).

hector_worldmodel: hector_object_tracker | hector_worldmodel_geotiff_plugins | hector_worldmodel_msgs

Package Summary

hector_object_tracker is the core package of hector_worldmodel. It listens to percept message from detectors (e.g. heat signatures of persons or recognitions of other objects of interest in the scene) and fuses all information to a single worldmodel state. Objects will be tracked over time and their states can be influenced by a couple of services. The percept to object association problem is solved either automatically based on the Mahalanobis distance, or a unique object_id can be given in the percept message. If a hector_nav_msgs/GetDistanceToObstacle service is available, the object_tracker can optionally deduce the depth of objects in the scene by projection to the nearest obstacle (wall).

hector_worldmodel: hector_object_tracker | hector_worldmodel_geotiff_plugins | hector_worldmodel_msgs

Package Summary

hector_object_tracker is the core package of hector_worldmodel. It listens to percept message from detectors (e.g. heat signatures of persons or recognitions of other objects of interest in the scene) and fuses all information to a single worldmodel state. Objects will be tracked over time and their states can be influenced by a couple of services. The percept to object association problem is solved either automatically based on the Mahalanobis distance, or a unique object_id can be given in the percept message. If a hector_nav_msgs/GetDistanceToObstacle service is available, the object_tracker can optionally deduce the depth of objects in the scene by projection to the nearest obstacle (wall).

hector_worldmodel: hector_object_tracker | hector_worldmodel_geotiff_plugins | hector_worldmodel_msgs

Package Summary

hector_object_tracker is the core package of hector_worldmodel. It listens to percept message from detectors (e.g. heat signatures of persons or recognitions of other objects of interest in the scene) and fuses all information to a single worldmodel state. Objects will be tracked over time and their states can be influenced by a couple of services. The percept to object association problem is solved either automatically based on the Mahalanobis distance, or a unique object_id can be given in the percept message. If a hector_nav_msgs/GetDistanceToObstacle service is available, the object_tracker can optionally deduce the depth of objects in the scene by projection to the nearest obstacle (wall).

Overview

This package provides a node for tracking the position of objects of interest as described in this paper

@INPROCEEDINGS{Meyer:2010:WorldModel,
  author = {J. Meyer and P. Schnitzspan and S. Kohlbrecher and K. Petersen and O. Schwahn and M. Andriluka and U. Klingauf and S. Roth and B. Schiele and O. von Stryk},
  title = {A Semantic World Model for Urban Search and Rescue Based on Heterogeneous Sensors},
  year = {2011},
  pages = {180 -- 193},
  editor = {Ruiz-del-Solar, Javier and Chown, Eric and Ploeger, Paul G.},
  series = {Lecture Notes in Computer Science, Lecture Notes in Artificial Intelligence},
  booktitle = {RoboCup 2010: Robot Soccer World Cup XIV},
  url = {https://springerlink3.metapress.com/content/n515v876ll57334l/resource-secured/?target=fulltext.pdf&sid=yyw2tr55m2on31z0hpufyw55&sh=www.springerlink.com},
}

ROS API

hector_object_tracker

hector_object_tracker is the central node of hector_worldmodel. It maintains a list of known objects in the environment and implements the association of incoming observations (percepts) and tracking. The observations have to be provided by at least one external node which implements a detector for certain object classes.

Subscribed Topics

worldmodel/image_percept (hector_worldmodel_msgs/ImagePercept)
  • An observation of an object represented by image coordinates, a camera info and an estimated distance (optional).
worldmodel/pose_percept (hector_worldmodel_msgs/PosePercept)
  • An observation of an object represented by a 3D pose.
worldmodel/update (hector_worldmodel_msgs/ObjectModel)
  • Update the object model with another model. Objects will be either added or fused.
syscommand (std_msgs/String)
  • System command. If the string equals "reset" the object database is cleared.

Published Topics

worldmodel/object (hector_worldmodel_msgs/Object)
  • Published for every update of an existing object or if a new object has been added.
worldmodel/objects (hector_worldmodel_msgs/ObjectModel)
  • The complete list of objects (latched). Republished for every update of the database.
visualization_marker (visualization_msgs/Marker)
  • Single marker publisher for each tracked object.
visualization_marker_array (visualization_msgs/MarkerArray)
  • Marker array publisher with annotated markers for each objects for visualization in rviz.

Services

worldmodel/get_object_model (hector_worldmodel_msgs/GetObjectModel) worldmodel/set_object_state (hector_worldmodel_msgs/SetObjectState)
  • Sets the internal state of an object (PENDING, ACTIVE, CONFIRMED, DISCARDED, ...). This state information is for interaction with a state machine and influences whether the object information is still updated or not.
worldmodel/set_object_name (hector_worldmodel_msgs/SetObjectName)
  • Sets the name field of an object identified by its object_id.
worldmodel/add_object (hector_worldmodel_msgs/AddObject)
  • Adds an object to the model or updates an existing one (without fusion).

Services Called

get_distance_to_obstacle (hector_nav_msgs/GetDistanceToObstacle)
  • Returns the distance to the next obstacle in the map in the direction of a view ray to project percepts. This service is implemented in hector_mapping. Service name can be overridden by the [class_id/]distance_to_obstacle_service parameter.
get_normal (hector_nav_msgs/GetNormal)
  • Returns the normal vector of the wall at a certain position. Used to fill the orientation of an object in the database, e.g. if there are objects at both sides of a wall. Service name has to be set explicitly with the [class_id/]get_normal_service parameter.
as specified by parameters (hector_worldmodel_msgs/VerifyPercept)
  • Plugin interface for percept verification services called for every incoming hector_worldmodel_msgs/ImagePercept or hector_worldmodel_msgs/PosePercept. Service servers can confirm or discard the percept based on its position in the camera frame (e.g. for thermal self-filtering). The list of verification services to be called has to be specified in the [class_id/]verification_services parameter.
as specified by parameters (hector_worldmodel_msgs/VerifyObject)
  • Plugin interface for object estimate verification called for every incoming hector_worldmodel_msgs/ImagePercept or hector_worldmodel_msgs/PosePercept. Service servers can confirm or discard the percept based on its mapped position and full state information. The list of verification services to be called has to be specified in the [class_id/]verification_services parameter.

Parameters

~frame_id (string, default: map)
  • The frame_id of the frame in which the objects are modeled.
~worldmodel_ns (string, default: worldmodel)
  • The namespace prefix for all worldmodel related topics and services.
~publish_interval (double, default: 0.0)
  • If greater than 0, republish the object model every x seconds.
~[class_id/]project_objects (boolean, default: false)
  • Project objects to the next obstacle in the map using the  get_distance_to_obstacle service.
~[class_id/]with_orientation (boolean, default: false)
  • Consider the orientation of objects as given in the percept or by the get_normal service during the association step.
~[class_id/]default_distance (double, default: 1.0)
  • Default object distance considered for image percepts without distance information (msg.distance == 0.0) if project_objects is false.
~[class_id/]distance_variance (double, default: 1.0^2)
  • Assumed variance of observations in distance (given in m^2).
~[class_id/]angle_variance (double, default: (10 degrees)^2)
  • Assumed variance of observations in (opening) angle (given in rad^2).
~[class_id/]min_height (double, default: -999.9)
  • Minimum z coordinate of objects. Percepts with a z coordinate which is smaller than this value will be discarded.
~[class_id/]max_height (double, default: 999.9)
  • Maximum z coordinate of objects. Percepts with a z coordinate which is greater than this value will be discarded.
~[class_id/]pending_support (double, default: 0)
  • Minimum support (added support of all percepts associated to the same object) where the object is automatically switched to the PENDING state.
~[class_id/]active_support (double, default: 0)
  • Minimum support (added support of all percepts associated to the same object) where the object is automatically switched to the ACTIVE state.
~[class_id/]inactive_support (double, default: 0)
  • If the support (added support of all percepts associated to the same object) drops below this value the object is automatically switched to the INACTIVE state.
~[class_id/]min_distance_between_objects (double, default: 0)
  • Objects which are closer to a CONFIRMED object than this distance will automatically be set to DISCARDED state.
~[class_id/]marker_color (double[], default: [0.8, 0, 0, 1.0] (red))
  • Color of the marker published for objects of this class (r,g,b,optionally a).
~[class_id/]distance_to_obstacle_service (string, default: get_distance_to_obstacle) ~[class_id/]get_normal_service (string, default: empty)
  • The hector_nav_msgs/GetNormal service to call for percepts of this class. The return value overwrites the orientation given in the percept message.
~negative_update[i]/topic (string)
  • The name of a sensor_msgs/CameraInfo topic to subscribe to. For each incoming message the support of every object within the field of view and within a certain minimal and maximum distance will be decreased.
~negative_update[i]/class_id (string)
  • Only apply this negative update for objects of class class_id.
~negative_update[i]/min_distance (double, default: 0)
  • Minimum estimated distance of the object
~negative_update[i]/max_distance (double, default: 0)
  • Maximum estimated distance of the object
~negative_update[i]/ignore_border_pixels (double, default: 0)
  • Minimum distance of the object from the image border in pixels
~negative_update[i]/not_seen_duration (double, default: 0 (off))
  • Only apply negative update if the object had no associated percept within the last x seconds.

See object_tracker.launch for a sample configuration.

Wiki: hector_object_tracker (last edited 2014-12-22 11:45:20 by JohannesMeyer)