STeF-map ROS implementation. STeF-map is a time-dependent probabilistic map able to model and predict flow patterns of people in indoor environments. The proposed representation models the likelihood of motion direction on a grid-based map by a set of harmonic functions, which efficiently capture long-term variations of crowd movements over time [1].
There are two modalities to run the STeF-map: Online or Offline
- Online: the aim of this one is to create the STeF-map as at the same time the robot is gathering the people detections.
- Offile: this modality is useful when the data has been already gathered and we want to built the STeF-map manually (no need of active topics) using data from the past.
/people_detections_1/2/3/4/5/6/7/8/9 (geometry_msgs/PoseArray)
Topics providing the people detections used later to build the histograms in each time interval and update the STeF-map.
/visibility_map (nav_msgs/OccupancyGrid)
Map showing the coverage applying ray tracing using the /coverage_scan topic.
Topic providing a map containg which cells of the environment are seen and which are not (Cells seen have a value of 100 and unseen cells have a value of 0).
The cells marked as seen are updated at the end of each time interval whether the was a human detection in them or not.
This is done to differenciate between cells that are seen but there was no detections and cells that are not seen and hence no data was available.
This topic can be computed with the "compute_visibility_map" node shown below.
Both the stefmap and the visibility map must have the same grid_size and dimensions (x_min, x_max, y_min, y_max) parameters.
/stefmap (stefmap_ros/STeFMapMsg)
This topic is published everytime the service ~get_stemap is called.
~get_stefmap (stefmap_ros/GetSTeFMap)
It returns a STeF-map prediction given a time (unix) and the model order (frequency components to use to calculate the output).
An example on how obtain stefmap prediction can be found in: https://github.com/sergimolina/stefmap_ros/blob/master/src/stefmap_client_currenttime.py
~grid_size (float, default: 1)
Cell size. Recommended between 0.5m and 2m.
~x_min (float, default: -50)
Minimum x value of the STeF-map.
~x_max (float, default: 50)
Maximum x value of the STeF-map.
~y_min (float, default: -50)
Minimum y value of the STeF-map.
~y_max (float, default: 50)
Maximum y value of the STeF-map.
~interval_time (int, default: 600)
Interval of time in seconds between STeF-map updates.
~num_bins (int, default: 8)
Number of bins discretising the full circumference. Recommended 8 or 12.
~frame_id (string, default: map)
The name of the STeF-map frame.
~people_detections_topic_1/2/3/4/5/6/7/8/9 (string, default: people_detections_1/2/3/4/5/6/7/8/9)
Name of the topic providing the people detections. Up to 9 topics can be defined as inputs
~load_data (bool, default: False)
Defines whether or not to load some data from the past before starting with the current updates.
~data_to_load_file (string, default: "test_data.txt")
Name of the file data to load if the 'load_data' parameter is set to True.
~save_histograms (bool, default: False)
Defines whether or not to save the histograms after every interval in to a file for later use.
~histograms_to_save_file (float, default: 5)
Name of the file data where to save the hiostrograms if the 'save_histograms' parameter is set to True.
As mentioned before this way of building the STeF-map is useful when we already have the people detection data.
None
/stefmap (stefmap_ros/STeFMapMsg)
This topic is published everytime the service ~get_stemap is called.
~get_stefmap (stefmap_ros/GetSTeFMap)
It provides a STeF-map prediction given a time (unix) and the model order (frequency components to use to calculate the output)
~update_stefmap (stefmap_ros/UpdateSTeFMap)
This service allows to update the STeF-map with the data provided.
An example on how to use this service can be found in: https://github.com/sergimolina/stefmap_ros/blob/master/scripts/tools/load_histograms.py
~grid_size (float, default: 1)
Cell size. Recommended between 0.5m and 2m.
~x_min (float, default: -50)
Minimum x value of the STeF-map.
~x_max (float, default: 50)
Maximum x value of the STeF-map.
~y_min (float, default: -50)
Minimum y value of the STeF-map.
~y_max (float, default: 50)
Maximum y value of the STeF-map.
~num_bins (int, default: 8)
Number of bins discretising the full circumference. Recommended 8 or 12.
~frame_id (string, default: map)
The name of the STeF-map frame.
Node to compute which cell of the environemtn are seen by the robot and which remain unseen.
/coverage_laser_robot_1/2/3/4/5/6/7/8/9 (sensor_msgs/LaserScan)
Scans used to perform ray tracing and define the cells that are seen by the robot.
Cell seen are marked as 100 and unseen as 0.
/visiblity_map (nav_msgs/OccupancyGrid)
Map showing the coverage applying ray tracing using the all the coverage_laser topics.
/robotX/visibility_map (nav_msgs/OccupancyGrid)
Map showing the coverage applying ray tracing using the corresponding coverage_laser_robot_X topic.
~get_visibility_map(stefmap_ros/GetVisibilityMap)
It returns the visiblity map when called.
~grid_size (float, default: 1)
Cell size (same as the defined for the stemap node)
~x_min (float, default: -50)
Minimum x value of the map (same as the defined for the stemap node)
~x_max (float, default: 50)
Maximum x value of the map (same as the defined for the stemap node)
~y_min (float, default: -50)
Minimum y value of the map (same as the defined for the stemap node)
~y_max (float, default: 50)
Maximum y value of the map (same as the defined for the stemap node)
~frame_id (string, default: map)
The name of the STeF-map frame (same as the defined for the stemap node)
~coverage_laser_robot_1/2/3/4/5/6/7/8/9 (string, default: coverage_scan_1/2/3/4/5/6/7/8/9)
/coverage_scan (sensor_msgs/LaserScan)
Scan used to perform ray tracing and define the cells that are seen by the robot.
Only the cells that can be seen are updated in each time interval.
This is done to differenciate between cells that are seen but there was no detections and cells that are not seen and hence no data was available.
~coverage_time_update (Float, default: 5)
Time interval between visiblity_map publish updates.
~max_coverage_distance (Float, default: 15)
Max distance used to apply ray tracing with the laser coverage scans.
Useful to limit the distance based on the human detection algorithm reliability.
~full_observability (Bool, default: False)
If set to True, all the cells in the map are marked as seen no matter the laser scan provided.
For further questions or doubts: sergimolina91@gmail.com
[1] S. Molina, G. Cielniak, T. Krajnik and T. Duckett. Modelling and Predicting Rhythmic Flow Patterns in Dyanmics Environments. In Towards AutonomousRobotic Systems (TAROS), volume 10965, pages 135–146, 2018.