Protected Member Functions | Protected Attributes | Private Attributes | List of all members
pcl_ros::CropBox Class Reference

CropBox is a filter that allows the user to filter all the data inside of a given box. More...

#include <crop_box.h>

Inheritance diagram for pcl_ros::CropBox:
Inheritance graph
[legend]

Protected Member Functions

bool child_init (ros::NodeHandle &nh, bool &has_service)
 Child initialization routine. More...
 
void config_callback (pcl_ros::CropBoxConfig &config, uint32_t level)
 Dynamic reconfigure service callback. More...
 
void filter (const PointCloud2::ConstPtr &input, const IndicesPtr &indices, PointCloud2 &output)
 Call the actual filter. More...
 
- Protected Member Functions inherited from pcl_ros::Filter
void computePublish (const PointCloud2::ConstPtr &input, const IndicesPtr &indices)
 Call the child filter () method, optionally transform the result, and publish it. More...
 
virtual void onInit ()
 Nodelet initialization routine. More...
 
virtual void subscribe ()
 Lazy transport subscribe routine. More...
 
virtual void unsubscribe ()
 Lazy transport unsubscribe routine. More...
 
- Protected Member Functions inherited from pcl_ros::PCLNodelet
bool isValid (const PointCloud2::ConstPtr &cloud, const std::string &topic_name="input")
 Test whether a given PointCloud message is "valid" (i.e., has points, and width and height are non-zero). More...
 
bool isValid (const PointCloudConstPtr &cloud, const std::string &topic_name="input")
 Test whether a given PointCloud message is "valid" (i.e., has points, and width and height are non-zero). More...
 
bool isValid (const PointIndicesConstPtr &indices, const std::string &topic_name="indices")
 Test whether a given PointIndices message is "valid" (i.e., has values). More...
 
bool isValid (const ModelCoefficientsConstPtr &model, const std::string &topic_name="model")
 Test whether a given ModelCoefficients message is "valid" (i.e., has values). More...
 
- Protected Member Functions inherited from nodelet_topic_tools::NodeletLazy
ros::Publisher advertise (ros::NodeHandle &nh, std::string topic, int queue_size, bool latch=false)
 
virtual void connectionCallback (const ros::SingleSubscriberPublisher &pub)
 
virtual void onInitPostProcess ()
 
virtual void warnNeverSubscribedCallback (const ros::WallTimerEvent &event)
 
- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::string & getName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 

Protected Attributes

boost::shared_ptr< dynamic_reconfigure::Server< pcl_ros::CropBoxConfig > > srv_
 Pointer to a dynamic reconfigure service. More...
 
- Protected Attributes inherited from pcl_ros::Filter
std::string filter_field_name_
 The desired user filter field name. More...
 
double filter_limit_max_
 The maximum allowed filter value a point will be considered from. More...
 
double filter_limit_min_
 The minimum allowed filter value a point will be considered from. More...
 
bool filter_limit_negative_
 Set to true if we want to return the data outside (filter_limit_min_;filter_limit_max_). Default: false. More...
 
boost::mutex mutex_
 Internal mutex. More...
 
ros::Subscriber sub_input_
 The input PointCloud subscriber. More...
 
message_filters::Subscriber< PointCloud2sub_input_filter_
 
std::string tf_input_frame_
 The input TF frame the data should be transformed into, if input.header.frame_id is different. More...
 
std::string tf_input_orig_frame_
 The original data input TF frame. More...
 
std::string tf_output_frame_
 The output TF frame the data should be transformed into, if input.header.frame_id is different. More...
 
- Protected Attributes inherited from pcl_ros::PCLNodelet
bool approximate_sync_
 True if we use an approximate time synchronizer versus an exact one (false by default). More...
 
bool latched_indices_
 Set to true if the indices topic is latched. More...
 
int max_queue_size_
 The maximum queue size (default: 3). More...
 
ros::Publisher pub_output_
 The output PointCloud publisher. More...
 
message_filters::Subscriber< PointIndicessub_indices_filter_
 The message filter subscriber for PointIndices. More...
 
message_filters::Subscriber< PointCloudsub_input_filter_
 The message filter subscriber for PointCloud2. More...
 
tf::TransformListener tf_listener_
 TF listener object. More...
 
bool use_indices_
 Set to true if point indices are used. More...
 
- Protected Attributes inherited from nodelet_topic_tools::NodeletLazy
boost::mutex connection_mutex_
 
ConnectionStatus connection_status_
 
bool ever_subscribed_
 
bool lazy_
 
boost::shared_ptr< ros::NodeHandlenh_
 
boost::shared_ptr< ros::NodeHandlepnh_
 
std::vector< ros::Publisherpublishers_
 
ros::WallTimer timer_ever_subscribed_
 
bool verbose_connection_
 

Private Attributes

pcl::CropBox< pcl::PCLPointCloud2 > impl_
 The PCL filter implementation used. More...
 

Additional Inherited Members

- Public Types inherited from pcl_ros::Filter
typedef boost::shared_ptr< const std::vector< int > > IndicesConstPtr
 
typedef boost::shared_ptr< std::vector< int > > IndicesPtr
 
typedef sensor_msgs::PointCloud2 PointCloud2
 
- Public Types inherited from pcl_ros::PCLNodelet
typedef boost::shared_ptr< const std::vector< int > > IndicesConstPtr
 
typedef boost::shared_ptr< std::vector< int > > IndicesPtr
 
typedef pcl_msgs::ModelCoefficients ModelCoefficients
 
typedef ModelCoefficients::ConstPtr ModelCoefficientsConstPtr
 
typedef ModelCoefficients::Ptr ModelCoefficientsPtr
 
typedef pcl::PointCloud< pcl::PointXYZ > PointCloud
 
typedef sensor_msgs::PointCloud2 PointCloud2
 
typedef PointCloud::ConstPtr PointCloudConstPtr
 
typedef PointCloud::Ptr PointCloudPtr
 
typedef pcl_msgs::PointIndices PointIndices
 
typedef PointIndices::ConstPtr PointIndicesConstPtr
 
typedef PointIndices::Ptr PointIndicesPtr
 
- Public Member Functions inherited from pcl_ros::Filter
 Filter ()
 
- Public Member Functions inherited from pcl_ros::PCLNodelet
 PCLNodelet ()
 Empty constructor. More...
 
- Public Member Functions inherited from nodelet_topic_tools::NodeletLazy
 NodeletLazy ()
 
- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
virtual ~Nodelet ()
 

Detailed Description

CropBox is a filter that allows the user to filter all the data inside of a given box.

Author
Radu Bogdan Rusu
Justin Rosen
Marti Morta Garriga

Definition at line 57 of file crop_box.h.

Member Function Documentation

bool pcl_ros::CropBox::child_init ( ros::NodeHandle nh,
bool &  has_service 
)
protectedvirtual

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 44 of file crop_box.cpp.

void pcl_ros::CropBox::config_callback ( pcl_ros::CropBoxConfig &  config,
uint32_t  level 
)
protected

Dynamic reconfigure service callback.

Parameters
configthe dynamic reconfigure CropBoxConfig object
levelthe dynamic reconfigure level

Definition at line 57 of file crop_box.cpp.

void pcl_ros::CropBox::filter ( const PointCloud2::ConstPtr &  input,
const IndicesPtr indices,
PointCloud2 output 
)
inlineprotectedvirtual

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 69 of file crop_box.h.

Member Data Documentation

pcl::CropBox<pcl::PCLPointCloud2> pcl_ros::CropBox::impl_
private

The PCL filter implementation used.

Definition at line 98 of file crop_box.h.

boost::shared_ptr<dynamic_reconfigure::Server<pcl_ros::CropBoxConfig> > pcl_ros::CropBox::srv_
protected

Pointer to a dynamic reconfigure service.

Definition at line 61 of file crop_box.h.


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


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Mon Jun 10 2019 14:19:18