pcd_io.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2009, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *
34  * $Id: pcd_io.h 35054 2011-01-03 21:16:49Z rusu $
35  *
36  */
37 
38 #ifndef PCL_ROS_IO_PCD_IO_H_
39 #define PCL_ROS_IO_PCD_IO_H_
40 
41 #include <pcl/io/pcd_io.h>
42 #include "pcl_ros/pcl_nodelet.h"
43 
44 namespace pcl_ros
45 {
47 
50  class PCDReader : public PCLNodelet
51  {
52  public:
53  typedef sensor_msgs::PointCloud2 PointCloud2;
54  typedef PointCloud2::Ptr PointCloud2Ptr;
55  typedef PointCloud2::ConstPtr PointCloud2ConstPtr;
56 
58  PCDReader () : publish_rate_ (0), tf_frame_ ("/base_link") {};
59 
60  virtual void onInit ();
61 
65  inline void setPublishRate (double publish_rate) { publish_rate_ = publish_rate; }
66 
68  inline double getPublishRate () { return (publish_rate_); }
69 
73  inline void setTFframe (std::string tf_frame) { tf_frame_ = tf_frame; }
74 
76  inline std::string getTFframe () { return (tf_frame_); }
77 
78  protected:
80  double publish_rate_;
81 
83  std::string tf_frame_;
84 
86  std::string file_name_;
87 
90 
91  private:
94  public:
95  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
96  };
97 
99 
102  class PCDWriter : public PCLNodelet
103  {
104  public:
105  PCDWriter () : file_name_ (""), binary_mode_ (true) {}
106 
107  typedef sensor_msgs::PointCloud2 PointCloud2;
108  typedef PointCloud2::Ptr PointCloud2Ptr;
109  typedef PointCloud2::ConstPtr PointCloud2ConstPtr;
110 
111  virtual void onInit ();
112  void input_callback (const PointCloud2ConstPtr &cloud);
113 
116 
117  protected:
119  std::string file_name_;
120 
123 
124  private:
127  public:
128  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
129  };
130 }
131 
132 #endif //#ifndef PCL_ROS_IO_PCD_IO_H_
pcl_ros::PCLNodelet
PCLNodelet represents the base PCL Nodelet class. All PCL nodelets should inherit from this class.
Definition: pcl_nodelet.h:73
pcl_ros::PCDWriter::PointCloud2ConstPtr
PointCloud2::ConstPtr PointCloud2ConstPtr
Definition: pcd_io.h:109
pcl_ros::PCDReader::file_name_
std::string file_name_
The name of the file that contains the PointCloud data.
Definition: pcd_io.h:86
pcl_ros
Definition: boundary.h:46
pcl_ros::PCDWriter::sub_input_
ros::Subscriber sub_input_
The input PointCloud subscriber.
Definition: pcd_io.h:115
pcl_ros::PCDWriter::PointCloud2
sensor_msgs::PointCloud2 PointCloud2
Definition: pcd_io.h:107
pcl_ros::PCDReader::PointCloud2
sensor_msgs::PointCloud2 PointCloud2
Definition: pcd_io.h:53
pcl_ros::PCDReader::setPublishRate
void setPublishRate(double publish_rate)
Set the publishing rate in seconds.
Definition: pcd_io.h:65
pcl_ros::PCDWriter::onInit
virtual void onInit()
Nodelet initialization routine. Reads in global parameters used by all nodelets.
Definition: pcd_io.cpp:136
pcl_nodelet.h
PCDWriter
pcl_ros::PCDWriter PCDWriter
Definition: pcd_io.cpp:179
pcl_ros::PCDReader
Point Cloud Data (PCD) file format reader.
Definition: pcd_io.h:50
pcl_ros::PCDReader::PointCloud2Ptr
PointCloud2::Ptr PointCloud2Ptr
Definition: pcd_io.h:54
pcl_ros::PCDReader::PointCloud2ConstPtr
PointCloud2::ConstPtr PointCloud2ConstPtr
Definition: pcd_io.h:55
pcl_ros::PCDReader::output_
PointCloud2Ptr output_
The output point cloud dataset containing the points loaded from the file.
Definition: pcd_io.h:89
pcl_ros::PCDReader::getPublishRate
double getPublishRate()
Get the publishing rate in seconds.
Definition: pcd_io.h:68
pcl_ros::PCDWriter::impl_
pcl::PCDWriter impl_
The PCL implementation used.
Definition: pcd_io.h:126
pcl_ros::PCDWriter::PCDWriter
PCDWriter()
Definition: pcd_io.h:105
pcl_ros::PCDWriter::PointCloud2Ptr
PointCloud2::Ptr PointCloud2Ptr
Definition: pcd_io.h:108
pcl_ros::PCDReader::impl_
pcl::PCDReader impl_
The PCL implementation used.
Definition: pcd_io.h:93
pcl_ros::PCDReader::getTFframe
std::string getTFframe()
Get the TF frame the PointCloud is published in.
Definition: pcd_io.h:76
pcl_ros::PCDReader::PCDReader
PCDReader()
Empty constructor.
Definition: pcd_io.h:58
pcl_ros::PCDWriter::file_name_
std::string file_name_
The name of the file that contains the PointCloud data.
Definition: pcd_io.h:119
pcl_ros::PCDWriter::binary_mode_
bool binary_mode_
Set to true if the output files should be saved in binary mode (true).
Definition: pcd_io.h:122
pcl_ros::PCDWriter
Point Cloud Data (PCD) file format writer.
Definition: pcd_io.h:102
PCDReader
pcl_ros::PCDReader PCDReader
Definition: pcd_io.cpp:178
pcl_ros::PCDReader::onInit
virtual void onInit()
Nodelet initialization routine. Reads in global parameters used by all nodelets.
Definition: pcd_io.cpp:43
pcl_ros::PCDWriter::input_callback
void input_callback(const PointCloud2ConstPtr &cloud)
Definition: pcd_io.cpp:156
pcl_ros::PCDReader::setTFframe
void setTFframe(std::string tf_frame)
Set the TF frame the PointCloud will be published in.
Definition: pcd_io.h:73
pcl_ros::PCDReader::tf_frame_
std::string tf_frame_
The TF frame the data should be published in ("/base_link" by default).
Definition: pcd_io.h:83
ros::Subscriber
pcl_ros::PCDReader::publish_rate_
double publish_rate_
The publishing interval in seconds. Set to 0 to only publish once (default).
Definition: pcd_io.h:80


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Fri Jul 12 2024 02:54:40