#include <filtering.h>
Public Member Functions | |
void | filter (const sensor_msgs::PointCloud2Ptr &msg) |
Callback function for subscriber. | |
filtering () | |
Class constructor. | |
sensor_msgs::PointCloud2 | voxel_filter (const sensor_msgs::PointCloud2Ptr &msg_in, double voxel_size) |
aplies a voxel grid on a sensor msg | |
~filtering () | |
Class destructor. | |
Public Attributes | |
PointCloud< T > | convex_hull |
The convex hull for cloud extraction. | |
string | frame_id |
The frame_id to transform. | |
double | max_z |
Maximum value for Z pointcloud. | |
double | min_z |
Minimum value for Z pointcloud. | |
PointCloud< T > | pc_in |
Point cloud to filter. | |
PointCloud< T > | pc_out |
Point cloud filtered. | |
ros::Publisher * | pub_ptr |
Pointer to pointcloud publisher. | |
tf::TransformListener * | transform_listener_ptr |
Pointer to a transform listener. | |
double | voxel_size |
Voxel grid size. |
A simple class to voxelize a pointcloud and cutt within a volume
Definition at line 61 of file filtering.h.
Class constructor.
Definition at line 66 of file filtering.h.
Class destructor.
Definition at line 71 of file filtering.h.
void filtering< T >::filter | ( | const sensor_msgs::PointCloud2Ptr & | msg | ) | [inline] |
Callback function for subscriber.
Pass through a square voxel grid
Transform to atc/center/bumper
Cutting the point cloud
Publish the result
Definition at line 38 of file filtering.hpp.
sensor_msgs::PointCloud2 filtering< T >::voxel_filter | ( | const sensor_msgs::PointCloud2Ptr & | msg_in, | |
double | voxel_size | |||
) | [inline] |
aplies a voxel grid on a sensor msg
[in] | msg_in | |
[in] | voxel_size |
Definition at line 78 of file filtering.hpp.
PointCloud<T> filtering< T >::convex_hull |
The convex hull for cloud extraction.
Definition at line 84 of file filtering.h.
The frame_id to transform.
Definition at line 102 of file filtering.h.
Maximum value for Z pointcloud.
Definition at line 90 of file filtering.h.
Minimum value for Z pointcloud.
Definition at line 93 of file filtering.h.
Point cloud to filter.
Definition at line 73 of file filtering.h.
Point cloud filtered.
Definition at line 81 of file filtering.h.
Pointer to pointcloud publisher.
Definition at line 96 of file filtering.h.
tf::TransformListener* filtering< T >::transform_listener_ptr |
Pointer to a transform listener.
Definition at line 99 of file filtering.h.
double filtering< T >::voxel_size |
Voxel grid size.
Definition at line 87 of file filtering.h.