pointcloudXYZIRT.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_POINTCLOUDXYZIRT_H
34 #define VELODYNE_POINTCLOUD_POINTCLOUDXYZIRT_H
35 
37 #include <string>
38 
39 namespace velodyne_pointcloud
40 {
42 {
43 public:
44  PointcloudXYZIRT(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);
46 
47  virtual void newLine();
48 
49  virtual void setup(const velodyne_msgs::VelodyneScan::ConstPtr& scan_msg);
50 
51  virtual void addPoint(float x, float y, float z, const uint16_t ring, const uint16_t azimuth,
52  const float distance, const float intensity, const float time);
53 
56 };
57 } // namespace velodyne_pointcloud
58 
59 #endif // VELODYNE_POINTCLOUD_POINTCLOUDXYZIRT_H
velodyne_pointcloud
Definition: calibration.h:40
velodyne_pointcloud::PointcloudXYZIRT::iter_intensity
sensor_msgs::PointCloud2Iterator< float > iter_intensity
Definition: pointcloudXYZIRT.h:54
velodyne_pointcloud::PointcloudXYZIRT::setup
virtual void setup(const velodyne_msgs::VelodyneScan::ConstPtr &scan_msg)
Definition: pointcloudXYZIRT.cc:25
datacontainerbase.h
velodyne_rawdata::DataContainerBase
Definition: datacontainerbase.h:47
velodyne_pointcloud::PointcloudXYZIRT::addPoint
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)
Definition: pointcloudXYZIRT.cc:38
sensor_msgs::PointCloud2Iterator< float >
velodyne_pointcloud::PointcloudXYZIRT
Definition: pointcloudXYZIRT.h:41
velodyne_pointcloud::PointcloudXYZIRT::newLine
virtual void newLine()
Definition: pointcloudXYZIRT.cc:35
velodyne_pointcloud::PointcloudXYZIRT::iter_y
sensor_msgs::PointCloud2Iterator< float > iter_y
Definition: pointcloudXYZIRT.h:54
velodyne_pointcloud::PointcloudXYZIRT::PointcloudXYZIRT
PointcloudXYZIRT(const double max_range, const double min_range, const std::string &target_frame, const std::string &fixed_frame, const unsigned int scans_per_block)
Definition: pointcloudXYZIRT.cc:8
velodyne_pointcloud::PointcloudXYZIRT::iter_ring
sensor_msgs::PointCloud2Iterator< uint16_t > iter_ring
Definition: pointcloudXYZIRT.h:55
velodyne_pointcloud::PointcloudXYZIRT::iter_z
sensor_msgs::PointCloud2Iterator< float > iter_z
Definition: pointcloudXYZIRT.h:54
velodyne_pointcloud::PointcloudXYZIRT::iter_x
sensor_msgs::PointCloud2Iterator< float > iter_x
Definition: pointcloudXYZIRT.h:54
velodyne_pointcloud::PointcloudXYZIRT::iter_time
sensor_msgs::PointCloud2Iterator< float > iter_time
Definition: pointcloudXYZIRT.h:54


velodyne_pointcloud
Author(s): Jack O'Quin, Piyush Khandelwal, Jesse Vera, Sebastian Pütz
autogenerated on Sun Jun 2 2024 02:29:13