ProAut PcdFilter

Introduction

This package was designed to remove simple geometric shapes from pointclouds. E.g. A cube or a sphere. Several of these filters can be applied to a pointcloud in one shot. For more details on the types of filters and their parameters see Filters.

This package includes a full node and a ros interface for one's own node. For more details about the node, like topic names and parameters, see Node.

The package can handle three different input types of pointclouds:

Additionaly the input data can be throttled to reduce the cpu load.

Node

rosrun pcdfilter_pa pcdfilter_pa_node
roslaunch pcdfilter_pa pcdfilter_pa.launch

Input and Output Topics:

Topic Name Type Description
"~/in_cloud" sensor_msgs/PointCloud2 Input as new pointcloud type.
"~/in_cloud_old" sensor_msgs/PointCloud Input as old pointloud type. Will be converted to new pointcloud type.
"~/in_laser" sensor_msgs/LaserScan Input as single laser scan. Will be converted to new pointcloud type by package "laser_geometry".
"~/out_cloud" sensor_msgs/PointCloud2 Output of filtering node.

All topics can be remapped using parameters (see below).

Services:

Service Name Type Description
"~/filter" pcdfilter_pa/PcdFilterPaCloud Forced filtering via service call. No throttling is done and input/output cloud is part of service message.
"~/add_filters" pcdfilter_pa/PcdFilterPaFilter Adding new filters. Old filters are kept.
"~/change_filters" pcdfilter_pa/PcdFilterPaFilter Adding new filters, but removing all old filters before adding.
"~/enable" std_srvs/Empty Disables this node. This also disconnects the node from all input messages.
"~/disable" std_srvs/Empty Enables this node.

Parameters:

Filter

Parameter Name Type Description
"~/filters" vector of strings All pointcloud filters as an array of strings.

general settings

Parameter Name Type Description
"~/skip_count" integer Input throttling. Number of skipped messages after each processed message.
"~/skip_time" double Input throttling. Time intervall in seconds. After each processed message, this intervall starts and all input messages will be skipped.
"~/tf_lookup_time" double Maximum time in seconds for waiting for a specific TF transform.
"~/buffer_pointcloud" bool Flag for buffering the last received pointcloud. This can be used to test different filters without resending the some pointcloud.
"~/debugging" bool Flag for enabling extented output.
"~/enabled" bool Flag for setting start up behaviour. Indicates if node is filtering at startup, or not.

laser

Parameter Name Type Description
"~/laser_nan_replacement_value" double If a nan-value is represented within the laser scan, it might indicate "no obstacle within range". Therefore this parameters will replace those values with a fixed number.

topics and services

Parameter Name Type Description
"~/topic_in_cloud" string Name of input topic for new pointclouds.
"~/topic_in_cloud_old" string Name of input topic for old pointclouds.
"~/topic_in_laser" string Name of input topic for laser scans.
"~/topic_out_cloud" string Name of output topic for filtered pointcloud.

See also this config file. It contains all parameters and their default value.

Filters

Definition: This is the definition of every single filter as a string.

[<inversion>]<type> <separator> <dimensions> <tf> [<tf_offset>] [<tf2> [<tf2_offset>]] [# <comment>]

Examples:

cube: 3 base_footprint

Filters every point within the following cube - the cube is removed from the pointcloud.
The sidelength is 3 [meters].
The center is aligned with TF frame "base_footprint".
Corners will be at [+/-1.5 , +/- 1.5, +/- 1.5].

!sphere: 2.3 map

Only points within sphere will stay.
The center of sphere is aligned with TF frame "map".
The radius is 2.3 [meters] and the diameter is 4.6 [meters].

block: 1 2 3 base_link 0.5 1 1.5

Removes every point within the cuboid.
One corner of the cuboid is at center of TF frame "base_link". This is due to the additional offset of [0.5, 1 1.5].
Two opposite corners are at [0, 0, 0] and [1, 2, 3].

link: 0.2 0 arm_link1 arm_link2

Removes every point within the cylinder, which is attached to both TF frames.
The center of the top and bottom surface is exactly at origin of one frame (zero overshoot).
The radius is 0.2 [meters].
The height depends only the relative position of the two frames.
Also the orientation of the cylinder is not fixed to any frame.

!cone: 10 1 laser pan_tilt_tilt_link

Removes every point outside the cone.
The top of cone will be at the origin of the TF frame "laser" and the centerline will go straight through the origin of the TF frame "pan_tilt_tilt_link".
The height is 10 [meters].
The angle at the top is 90 degrees (ratio of radius to height is 1:1).

Links and packages

Source code at github:

Related packages:

ROS packages:

ROS Documentation

ROS-Distribution Documentation
Indigo docs.ros.org
Jade (EOL May 2017) docs.ros.org
Kinetic docs.ros.org
Lunar docs.ros.org


pcdfilter_pa
Author(s):
autogenerated on Fri Jun 7 2019 21:53:31