Go to the documentation of this file.
   52   NODELET_DEBUG (
"[%s::onInit] Nodelet successfully created with the following parameters:\n" 
   53                  " - publish_rate : %f\n" 
   59   output_ = boost::make_shared<PointCloud2> ();
 
   60   output_new = boost::make_shared<PointCloud2> ();
 
   71   std::string file_name;
 
   78       ROS_ERROR_ONCE (
"[%s::onInit] Need a 'filename' parameter to be set before continuing!", 
getName ().c_str ());
 
   89       pcl::PCLPointCloud2 cloud;
 
  101     if (
output_->data.size () == 0)
 
  142   pnh_->getParam (
"filename", file_name_);
 
  143   pnh_->getParam (
"binary_mode", binary_mode_);
 
  145   NODELET_DEBUG (
"[%s::onInit] Nodelet successfully created with the following parameters:\n" 
  147                  " - binary_mode  : %s", 
 
  149                  file_name_.c_str (), (binary_mode_) ? 
"true" : 
"false");
 
  151   onInitPostProcess ();
 
  158   if (!isValid (cloud))
 
  161   pnh_->getParam (
"filename", file_name_);
 
  163   NODELET_DEBUG (
"[%s::input_callback] PointCloud with %d data points and frame %s on topic %s received.", 
getName ().c_str (), cloud->width * cloud->height, cloud->header.frame_id.c_str (), getMTPrivateNodeHandle ().resolveName (
"input").c_str ());
 
  166   if (file_name_.empty ())
 
  167     fname = boost::lexical_cast<std::string> (cloud->header.stamp.toSec ()) + 
".pcd";
 
  170   pcl::PCLPointCloud2 pcl_cloud;
 
  173   impl_.write (fname, pcl_cloud, Eigen::Vector4f::Zero (), Eigen::Quaternionf::Identity (), binary_mode_);
 
  
#define NODELET_ERROR(...)
PointCloud2::ConstPtr PointCloud2ConstPtr
#define ROS_ERROR_ONCE(...)
std::string file_name_
The name of the file that contains the PointCloud data.
ROSCONSOLE_CONSOLE_IMPL_DECL std::string getName(void *handle)
ROSCPP_DECL void spinOnce()
ros::NodeHandle & getMTPrivateNodeHandle() const
sensor_msgs::PointCloud2 PointCloud2
sensor_msgs::PointCloud2 PointCloud2
virtual void onInit()
Nodelet initialization routine. Reads in global parameters used by all nodelets.
void publish(const boost::shared_ptr< M > &message) const
pcl_ros::PCDWriter PCDWriter
Point Cloud Data (PCD) file format reader.
PointCloud2::Ptr PointCloud2Ptr
PointCloud2Ptr output_
The output point cloud dataset containing the points loaded from the file.
int max_queue_size_
The maximum queue size (default: 3).
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
virtual void onInit()
Nodelet initialization routine. Reads in global parameters used by all nodelets.
void moveToPCL(pcl_msgs::ModelCoefficients &mc, pcl::ModelCoefficients &pcl_mc)
pcl::PCDReader impl_
The PCL implementation used.
#define NODELET_INFO(...)
#define ROS_DEBUG_ONCE(...)
Point Cloud Data (PCD) file format writer.
const std::string & getName() const
pcl_ros::PCDReader PCDReader
uint32_t getNumSubscribers() const
virtual void onInit()
Nodelet initialization routine. Reads in global parameters used by all nodelets.
void input_callback(const PointCloud2ConstPtr &cloud)
std::string tf_frame_
The TF frame the data should be published in ("/base_link" by default).
void moveFromPCL(pcl::ModelCoefficients &pcl_mc, pcl_msgs::ModelCoefficients &mc)
#define NODELET_DEBUG(...)
double publish_rate_
The publishing interval in seconds. Set to 0 to only publish once (default).
pcl_ros
Author(s): Open Perception, Julius Kammerl 
, William Woodall 
autogenerated on Fri Jul 12 2024 02:54:40