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 ());
157 isValid (
const PointCloudConstPtr &cloud,
const std::string &topic_name =
"input")
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 ());
173 isValid (
const PointIndicesConstPtr &,
const std::string & =
"indices")
188 isValid (
const ModelCoefficientsConstPtr &,
const std::string & =
"model")
209 pnh_->getParam (
"max_queue_size", max_queue_size_);
212 pnh_->getParam (
"use_indices", use_indices_);
213 pnh_->getParam (
"latched_indices", latched_indices_);
214 pnh_->getParam (
"approximate_sync", approximate_sync_);
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",
222 (approximate_sync_) ?
"true" :
"false",
223 (use_indices_) ?
"true" :
"false",
224 (latched_indices_) ?
"true" :
"false",
229 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
233 #endif //#ifndef PCL_NODELET_H_ pcl_msgs::ModelCoefficients ModelCoefficients
PointIndices::Ptr PointIndicesPtr
virtual void onInit()
Nodelet initialization routine. Reads in global parameters used by all nodelets.
#define NODELET_WARN(...)
ModelCoefficients::Ptr ModelCoefficientsPtr
PCLNodelet()
Empty constructor.
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...
message_filters::Subscriber< PointIndices > sub_indices_filter_
The message filter subscriber for PointIndices.
pcl::IndicesConstPtr IndicesConstPtr
bool isValid(const ModelCoefficientsConstPtr &, const std::string &="model")
Test whether a given ModelCoefficients message is "valid" (i.e., has values).
bool latched_indices_
Set to true if the indices topic is latched.
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...
const std::string & getName() const
bool isValid(const PointIndicesConstPtr &, const std::string &="indices")
Test whether a given PointIndices message is "valid" (i.e., has values).
sensor_msgs::PointCloud2 PointCloud2
boost::shared_ptr< const PointCloud > PointCloudConstPtr
PCLNodelet represents the base PCL Nodelet class. All PCL nodelets should inherit from this class...
pcl_msgs::PointIndices PointIndices
boost::shared_ptr< PointCloud > PointCloudPtr
virtual void unsubscribe()
pcl::PointCloud< pcl::PointXYZ > PointCloud
tf::TransformListener tf_listener_
TF listener object.
bool approximate_sync_
True if we use an approximate time synchronizer versus an exact one (false by default).
pcl::IndicesPtr IndicesPtr
virtual void subscribe()
Lazy transport subscribe/unsubscribe routine. It is optional for backward compatibility.
int max_queue_size_
The maximum queue size (default: 3).
ModelCoefficients::ConstPtr ModelCoefficientsConstPtr
ros::Publisher pub_output_
The output PointCloud publisher.
void fromPCL(const std::uint64_t &pcl_stamp, ros::Time &stamp)
#define NODELET_DEBUG(...)
bool use_indices_
Set to true if point indices are used.
PointIndices::ConstPtr PointIndicesConstPtr
message_filters::Subscriber< PointCloud > sub_input_filter_
The message filter subscriber for PointCloud2.