Wiki

Overview

The non persistent voxel layer incorporate information from the sensors in the form of PointClouds or LaserScans. This information is converted into 3D and populated into a temporary voxel_grid for each sensor cycle.

ROS drop in replacement to the voxel layer which does not persist readings through iterations when ray tracing or map maintenance is undesirable.

Created in response to need for a rolling local costmap layer to not persist readings due to a specific sensor being used. After looking through the community, it seems several people on ros answers have asked for a similar tool. This is to make that possible.

Source and bug tracker: https://github.com/SteveMacenski/nonpersistent_voxel_layer

Maintainer: Steve Macenski <stevenmacenski AT gmail DOT com>

Author: Steve Macenski, based on work from: Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com

Marking

The costmap automatically subscribes to sensors topics and updates itself accordingly. Each sensor is used to mark. With the voxel layer, obstacle information from each column is projected down into two dimensions when put into the costmap. The non-persistent voxel layer does not do any clearing and resets each sensor cycle.

ROS API

Same API applies to this layer as to the voxel layer, except for the clearing operations.

Subscribed Topics

<point_cloud_topic> (sensor_msgs/PointCloud) <point_cloud2_topic> (sensor_msgs/PointCloud2) <laser_scan_topic> (sensor_msgs/LaserScan) "map" (nav_msgs/OccupancyGrid)

Sensor management parameters

~<name>/observation_sources (string, default: "")

Each source_name in observation_sources defines a namespace in which parameters can be set:

~<name>/<source_name>/topic (string, default: source_name)

~<name>/<source_name>/sensor_frame (string, default: "") ~<name>/<source_name>/observation_persistence (double, default: 0.0) ~<name>/<source_name>/expected_update_rate (double, default: 0.0) ~<name>/<source_name>/data_type (string, default: "PointCloud") ~<name>/<source_name>/marking (bool, default: true) ~<name>/<source_name>/max_obstacle_height (double, default: 2.0) ~<name>/<source_name>/min_obstacle_height (double, default: 0.0) ~<name>/<source_name>/obstacle_range (double, default: 2.5) ~<name>/<source_name>/raytrace_range (double, default: 3.0) ~<name>/<source_name>/inf_is_valid (bool, default: false)

Global Filtering Parameters

These parameters apply to all sensors.

~<name>/max_obstacle_height (double, default: 2.0)

~<name>/obstacle_range (double, default: 2.5)

NonPersistentVoxelCostmapPlugin

The following parameters are used by the NonPersistentVoxelCostmapPlugin.

~<name>/origin_z (double, default: 0.0)

~<name>/z_resolution (double, default: 0.2) ~<name>/z_voxels (int, default: 10) ~<name>/unknown_threshold (int, default: ~<name>/z_voxels) ~<name>/mark_threshold (int, default: 0) ~<name>/publish_voxel_map (bool, default: false) ~<name>/footprint_clearing_enabled (bool, default: true)

Wiki: nonpersistent_voxel_grid (last edited 2018-05-16 01:25:29 by SteveMacenski)