Go to the documentation of this file.
44 #ifndef PCL_NODELET_H_
45 #define PCL_NODELET_H_
47 #include <sensor_msgs/PointCloud2.h>
49 #include <pcl_msgs/PointIndices.h>
50 #include <pcl_msgs/ModelCoefficients.h>
51 #include <pcl/pcl_base.h>
52 #include <pcl/point_types.h>
141 isValid (
const PointCloud2::ConstPtr &cloud,
const std::string &topic_name =
"input")
143 if (cloud->width * cloud->height * cloud->point_step != cloud->data.size ())
145 NODELET_WARN (
"[%s] Invalid PointCloud (data = %zu, width = %d, height = %d, step = %d) with stamp %f, and frame %s on topic %s received!",
getName ().c_str (), cloud->data.size (), cloud->width, cloud->height, cloud->point_step, cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (),
pnh_->resolveName (topic_name).c_str ());
159 if (cloud->width * cloud->height != cloud->points.size ())
161 NODELET_WARN (
"[%s] Invalid PointCloud (points = %zu, width = %d, height = %d) with stamp %f, and frame %s on topic %s received!",
getName ().c_str (), cloud->points.size (), cloud->width, cloud->height,
fromPCL(cloud->header).stamp.toSec (), cloud->header.frame_id.c_str (),
pnh_->resolveName (topic_name).c_str ());
216 NODELET_DEBUG (
"[%s::onInit] PCL Nodelet successfully created with the following parameters:\n"
217 " - approximate_sync : %s\n"
218 " - use_indices : %s\n"
219 " - latched_indices : %s\n"
220 " - max_queue_size : %d",
229 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
233 #endif //#ifndef PCL_NODELET_H_
bool latched_indices_
Set to true if the indices topic is latched.
bool approximate_sync_
True if we use an approximate time synchronizer versus an exact one (false by default).
tf::TransformListener tf_listener_
TF listener object.
message_filters::Subscriber< PointIndices > sub_indices_filter_
The message filter subscriber for PointIndices.
PCLNodelet represents the base PCL Nodelet class. All PCL nodelets should inherit from this class.
bool isValid(const PointIndicesConstPtr &, const std::string &="indices")
Test whether a given PointIndices message is "valid" (i.e., has values).
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-ze...
sensor_msgs::PointCloud2 PointCloud2
bool use_indices_
Set to true if point indices are used.
#define NODELET_WARN(...)
boost::shared_ptr< const PointCloud > PointCloudConstPtr
boost::shared_ptr< PointCloud > PointCloudPtr
PointIndices::ConstPtr PointIndicesConstPtr
virtual void unsubscribe()
pcl::PointCloud< pcl::PointXYZ > PointCloud
pcl_msgs::ModelCoefficients ModelCoefficients
void fromPCL(const pcl::ModelCoefficients &pcl_mc, pcl_msgs::ModelCoefficients &mc)
int max_queue_size_
The maximum queue size (default: 3).
pcl::IndicesPtr IndicesPtr
ros::Publisher pub_output_
The output PointCloud publisher.
virtual void onInit()
Nodelet initialization routine. Reads in global parameters used by all nodelets.
virtual void subscribe()
Lazy transport subscribe/unsubscribe routine. It is optional for backward compatibility.
ModelCoefficients::Ptr ModelCoefficientsPtr
ModelCoefficients::ConstPtr ModelCoefficientsConstPtr
message_filters::Subscriber< PointCloud > sub_input_filter_
The message filter subscriber for PointCloud2.
pcl::IndicesConstPtr IndicesConstPtr
PointIndices::Ptr PointIndicesPtr
const std::string & getName() const
PCLNodelet()
Empty constructor.
pcl_msgs::PointIndices PointIndices
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-ze...
#define NODELET_DEBUG(...)
bool isValid(const ModelCoefficientsConstPtr &, const std::string &="model")
Test whether a given ModelCoefficients message is "valid" (i.e., has values).
pcl_ros
Author(s): Open Perception, Julius Kammerl
, William Woodall
autogenerated on Fri Jul 12 2024 02:54:40