pcl_conversions_indigo.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Open Source Robotics Foundation, 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 Open Source Robotics Foundation, Inc. nor
18  * the names of its contributors may be used to endorse or promote
19  * products derived from this software without specific prior
20  * written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  */
35 
36 #ifndef INDIGO_PCL_CONVERSIONS_H__
37 #define INDIGO_PCL_CONVERSIONS_H__
38 
39 #include <vector>
40 
41 #include <ros/ros.h>
42 
43 #include <pcl/conversions.h>
44 
45 #include <pcl/PCLHeader.h>
46 #include <std_msgs/Header.h>
47 
48 #include <pcl/PCLImage.h>
49 #include <sensor_msgs/Image.h>
50 
51 #include <pcl/PCLPointField.h>
52 #include <sensor_msgs/PointField.h>
53 
54 #include <pcl/PCLPointCloud2.h>
55 #include <sensor_msgs/PointCloud2.h>
56 
57 #include <pcl/PointIndices.h>
58 #include <pcl_msgs/PointIndices.h>
59 
60 #include <pcl/ModelCoefficients.h>
61 #include <pcl_msgs/ModelCoefficients.h>
62 
63 #include <pcl/Vertices.h>
64 #include <pcl_msgs/Vertices.h>
65 
66 #include <pcl/PolygonMesh.h>
67 #include <pcl_msgs/PolygonMesh.h>
68 
69 #include <pcl/io/pcd_io.h>
70 
71 #include <Eigen/StdVector>
72 #include <Eigen/Geometry>
73 
74 namespace pcl_conversions {
75 
78  inline
79  void fromPCL(const pcl::uint64_t &pcl_stamp, ros::Time &stamp)
80  {
81  stamp.fromNSec(pcl_stamp * 1e3); // Convert from us to ns
82  }
83 
84  inline
85  void toPCL(const ros::Time &stamp, pcl::uint64_t &pcl_stamp)
86  {
87  pcl_stamp = stamp.toNSec() / 1e3; // Convert from ns to us
88  }
89 
90  inline
91  ros::Time fromPCL(const pcl::uint64_t &pcl_stamp)
92  {
93  ros::Time stamp;
94  fromPCL(pcl_stamp, stamp);
95  return stamp;
96  }
97 
98  inline
99  pcl::uint64_t toPCL(const ros::Time &stamp)
100  {
101  pcl::uint64_t pcl_stamp;
102  toPCL(stamp, pcl_stamp);
103  return pcl_stamp;
104  }
105 
108  //inline
109  //void fromPCL(const pcl::PCLHeader &pcl_header, std_msgs::Header &header)
110  //{
111  //fromPCL(pcl_header.stamp, header.stamp);
112  //header.seq = pcl_header.seq;
113  //header.frame_id = pcl_header.frame_id;
114  //}
115 
116  //inline
117  //void toPCL(const std_msgs::Header &header, pcl::PCLHeader &pcl_header)
118  //{
119  //toPCL(header.stamp, pcl_header.stamp);
120  //pcl_header.seq = header.seq;
121  //pcl_header.frame_id = header.frame_id;
122  //}
123 
124  //inline
125  //std_msgs::Header fromPCL(const pcl::PCLHeader &pcl_header)
126  //{
127  //std_msgs::Header header;
128  //fromPCL(pcl_header, header);
129  //return header;
130  //}
131 
132  //inline
133  //pcl::PCLHeader toPCL(const std_msgs::Header &header)
134  //{
135  //pcl::PCLHeader pcl_header;
136  //toPCL(header, pcl_header);
137  //return pcl_header;
138  //}
139 
140 }
141 
142 #endif
Time & fromNSec(uint64_t t)
void fromPCL(const pcl::uint64_t &pcl_stamp, ros::Time &stamp)
uint64_t toNSec() const
void toPCL(const ros::Time &stamp, pcl::uint64_t &pcl_stamp)


feature_tracker
Author(s): Roberto Martín-Martín
autogenerated on Mon Jun 10 2019 14:06:08