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)
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");
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_);
PointCloud2Ptr output_
The output point cloud dataset containing the points loaded from the file.
pcl_ros::PCDWriter PCDWriter
#define NODELET_ERROR(...)
virtual void onInit()
Nodelet initialization routine. Reads in global parameters used by all nodelets.
std::string file_name_
The name of the file that contains the PointCloud data.
Point Cloud Data (PCD) file format reader.
#define ROS_DEBUG_ONCE(...)
void input_callback(const PointCloud2ConstPtr &cloud)
double publish_rate_
The publishing interval in seconds. Set to 0 to only publish once (default).
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...
virtual void onInit()
Nodelet initialization routine. Reads in global parameters used by all nodelets.
ros::NodeHandle & getMTPrivateNodeHandle() const
const std::string & getName() const
sensor_msgs::PointCloud2 PointCloud2
void publish(const boost::shared_ptr< M > &message) const
PointCloud2::ConstPtr PointCloud2ConstPtr
PointCloud2::Ptr PointCloud2Ptr
#define ROS_ERROR_ONCE(...)
std::string resolveName(const std::string &name, bool remap=true) const
#define NODELET_INFO(...)
std::string tf_frame_
The TF frame the data should be published in ("/base_link" by default).
virtual void onInit()
Nodelet initialization routine. Reads in global parameters used by all nodelets.
int max_queue_size_
The maximum queue size (default: 3).
void moveFromPCL(pcl::PCLImage &pcl_image, sensor_msgs::Image &image)
uint32_t getNumSubscribers() const
Point Cloud Data (PCD) file format writer.
pcl::PCDReader impl_
The PCL implementation used.
ROSCPP_DECL void spinOnce()
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
#define NODELET_DEBUG(...)
void moveToPCL(sensor_msgs::Image &image, pcl::PCLImage &pcl_image)
PCDReader()
Empty constructor.