Program Listing for File pcd_io.hpp
↰ Return to documentation for file (/tmp/ws/src/perception_pcl/pcl_ros/include/pcl_ros/io/pcd_io.hpp
)
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2009, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Willow Garage, Inc. nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
* $Id: pcd_io.h 35054 2011-01-03 21:16:49Z rusu $
*
*/
#ifndef PCL_ROS__IO__PCD_IO_HPP_
#define PCL_ROS__IO__PCD_IO_HPP_
#include <pcl/io/pcd_io.h>
#include <string>
#include "pcl_ros/pcl_nodelet.hpp"
namespace pcl_ros
{
class PCDReader : public PCLNodelet
{
public:
typedef sensor_msgs::PointCloud2 PointCloud2;
typedef PointCloud2::Ptr PointCloud2Ptr;
typedef PointCloud2::ConstPtr PointCloud2ConstPtr;
PCDReader()
: publish_rate_(0), tf_frame_("/base_link") {}
virtual void onInit();
inline void setPublishRate(double publish_rate) {publish_rate_ = publish_rate;}
inline double getPublishRate() {return publish_rate_;}
inline void setTFframe(std::string tf_frame) {tf_frame_ = tf_frame;}
inline std::string getTFframe() {return tf_frame_;}
protected:
double publish_rate_;
std::string tf_frame_;
std::string file_name_;
PointCloud2Ptr output_;
private:
pcl::PCDReader impl_;
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};
class PCDWriter : public PCLNodelet
{
public:
PCDWriter()
: file_name_(""), binary_mode_(true) {}
typedef sensor_msgs::PointCloud2 PointCloud2;
typedef PointCloud2::Ptr PointCloud2Ptr;
typedef PointCloud2::ConstPtr PointCloud2ConstPtr;
virtual void onInit();
void input_callback(const PointCloud2ConstPtr & cloud);
ros::Subscriber sub_input_;
protected:
std::string file_name_;
bool binary_mode_;
private:
pcl::PCDWriter impl_;
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};
} // namespace pcl_ros
#endif // PCL_ROS__IO__PCD_IO_HPP_