Protected Member Functions | Protected Attributes | Private Attributes
segbot_sensors::SegbotVelodyneOutlierRemoval Class Reference

#include <segbot_velodyne_outlier_removal.h>

Inheritance diagram for segbot_sensors::SegbotVelodyneOutlierRemoval:
Inheritance graph
[legend]

List of all members.

Protected Member Functions

bool child_init (ros::NodeHandle &nh, bool &has_service)
 Child initialization routine.
void config_callback (segbot_sensors::SegbotVelodyneOutlierRemovalConfig &config, uint32_t level)
 Dynamic reconfigure callback.
void filter (const PointCloud2::ConstPtr &input, const IndicesPtr &indices, PointCloud2 &output)
 Call the actual filter.

Protected Attributes

boost::shared_ptr
< dynamic_reconfigure::Server
< SegbotVelodyneOutlierRemovalConfig > > 
srv_
 Pointer to a dynamic reconfigure service.

Private Attributes

std::vector< geometry_msgs::Pointfootprint_
boost::shared_ptr< ros::Publisherfootprint_publisher_
std::string frame_

Detailed Description

Definition at line 163 of file segbot_velodyne_outlier_removal.h.


Member Function Documentation

bool segbot_sensors::SegbotVelodyneOutlierRemoval::child_init ( ros::NodeHandle nh,
bool &  has_service 
) [protected, virtual]

Child initialization routine.

Parameters:
nhROS node handle
has_serviceset to true if the child has a Dynamic Reconfigure service

Reimplemented from pcl_ros::Filter.

Definition at line 244 of file segbot_velodyne_outlier_removal.cpp.

void segbot_sensors::SegbotVelodyneOutlierRemoval::config_callback ( segbot_sensors::SegbotVelodyneOutlierRemovalConfig &  config,
uint32_t  level 
) [protected]

Dynamic reconfigure callback.

Parameters:
configthe config object
levelthe dynamic reconfigure level

Definition at line 258 of file segbot_velodyne_outlier_removal.cpp.

void segbot_sensors::SegbotVelodyneOutlierRemoval::filter ( const PointCloud2::ConstPtr &  input,
const IndicesPtr indices,
PointCloud2 output 
) [inline, protected, virtual]

Call the actual filter.

Parameters:
inputthe input point cloud dataset
indicesthe input set of indices to use from input
outputthe resultant filtered dataset

Implements pcl_ros::Filter.

Definition at line 175 of file segbot_velodyne_outlier_removal.h.


Member Data Documentation

Definition at line 223 of file segbot_velodyne_outlier_removal.h.

Definition at line 224 of file segbot_velodyne_outlier_removal.h.

Definition at line 225 of file segbot_velodyne_outlier_removal.h.

boost::shared_ptr<dynamic_reconfigure::Server<SegbotVelodyneOutlierRemovalConfig> > segbot_sensors::SegbotVelodyneOutlierRemoval::srv_ [protected]

Pointer to a dynamic reconfigure service.

Reimplemented from pcl_ros::Filter.

Definition at line 167 of file segbot_velodyne_outlier_removal.h.


The documentation for this class was generated from the following files:


segbot_sensors
Author(s): Piyush Khandelwal
autogenerated on Thu Jun 6 2019 21:37:13