pointcloudXYZIR.h
Go to the documentation of this file.
1 // Copyright (C) 2012, 2019 Austin Robot Technology, Jack O'Quin, Joshua Whitley, Sebastian Pütz
2 // All rights reserved.
3 //
4 // Software License Agreement (BSD License 2.0)
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions
8 // are met:
9 //
10 // * Redistributions of source code must retain the above copyright
11 // notice, this list of conditions and the following disclaimer.
12 // * Redistributions in binary form must reproduce the above
13 // copyright notice, this list of conditions and the following
14 // disclaimer in the documentation and/or other materials provided
15 // with the distribution.
16 // * Neither the name of {copyright_holder} nor the names of its
17 // contributors may be used to endorse or promote products derived
18 // from this software without specific prior written permission.
19 //
20 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 // COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 // INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 // BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 // POSSIBILITY OF SUCH DAMAGE.
32 
33 #ifndef VELODYNE_POINTCLOUD_POINTCLOUDXYZIR_H
34 #define VELODYNE_POINTCLOUD_POINTCLOUDXYZIR_H
35 
37 #include <string>
38 
39 namespace velodyne_pointcloud
40 {
42 {
43 public:
44  PointcloudXYZIR(const double max_range, const double min_range, const std::string& target_frame,
45  const std::string& fixed_frame, const unsigned int scans_per_block,
47 
48  virtual void newLine();
49 
50  virtual void setup(const velodyne_msgs::VelodyneScan::ConstPtr& scan_msg);
51 
52  virtual void addPoint(float x, float y, float z, const uint16_t ring, const uint16_t azimuth,
53  const float distance, const float intensity, const float time);
54 
57 };
58 } // namespace velodyne_pointcloud
59 
60 #endif // VELODYNE_POINTCLOUD_POINTCLOUDXYZIR_H
sensor_msgs::PointCloud2Iterator< float > iter_z
sensor_msgs::PointCloud2Iterator< float > iter_y
sensor_msgs::PointCloud2Iterator< uint16_t > iter_ring
sensor_msgs::PointCloud2Iterator< float > iter_time
virtual void addPoint(float x, float y, float z, const uint16_t ring, const uint16_t azimuth, const float distance, const float intensity, const float time)
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
sensor_msgs::PointCloud2Iterator< float > iter_x
TFSIMD_FORCE_INLINE const tfScalar & y() const
boost::shared_ptr< tf::TransformListener > tf_ptr
transform listener
virtual void setup(const velodyne_msgs::VelodyneScan::ConstPtr &scan_msg)
TFSIMD_FORCE_INLINE const tfScalar & x() const
TFSIMD_FORCE_INLINE const tfScalar & z() const
PointcloudXYZIR(const double max_range, const double min_range, const std::string &target_frame, const std::string &fixed_frame, const unsigned int scans_per_block, boost::shared_ptr< tf::TransformListener > tf_ptr=boost::shared_ptr< tf::TransformListener >())
sensor_msgs::PointCloud2Iterator< float > iter_intensity


velodyne_pointcloud
Author(s): Jack O'Quin, Piyush Khandelwal, Jesse Vera, Sebastian Pütz
autogenerated on Sun Sep 6 2020 03:25:30