00001 // Copyright (C) 2012, 2019 Austin Robot Technology, Jack O'Quin, Joshua Whitley, Sebastian Pütz 00002 // All rights reserved. 00003 // 00004 // Software License Agreement (BSD License 2.0) 00005 // 00006 // Redistribution and use in source and binary forms, with or without 00007 // modification, are permitted provided that the following conditions 00008 // are met: 00009 // 00010 // * Redistributions of source code must retain the above copyright 00011 // notice, this list of conditions and the following disclaimer. 00012 // * Redistributions in binary form must reproduce the above 00013 // copyright notice, this list of conditions and the following 00014 // disclaimer in the documentation and/or other materials provided 00015 // with the distribution. 00016 // * Neither the name of {copyright_holder} nor the names of its 00017 // contributors may be used to endorse or promote products derived 00018 // from this software without specific prior written permission. 00019 // 00020 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00021 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00022 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00023 // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00024 // COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00025 // INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00026 // BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00027 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00028 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00029 // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00030 // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00031 // POSSIBILITY OF SUCH DAMAGE. 00032 00033 #ifndef VELODYNE_POINTCLOUD_POINTCLOUDXYZIR_H 00034 #define VELODYNE_POINTCLOUD_POINTCLOUDXYZIR_H 00035 00036 #include <velodyne_pointcloud/datacontainerbase.h> 00037 #include <string> 00038 00039 namespace velodyne_pointcloud 00040 { 00041 class PointcloudXYZIR : public velodyne_rawdata::DataContainerBase 00042 { 00043 public: 00044 PointcloudXYZIR(const double max_range, const double min_range, const std::string& target_frame, 00045 const std::string& fixed_frame, const unsigned int scans_per_block, 00046 boost::shared_ptr<tf::TransformListener> tf_ptr = boost::shared_ptr<tf::TransformListener>()); 00047 00048 virtual void newLine(); 00049 00050 virtual void setup(const velodyne_msgs::VelodyneScan::ConstPtr& scan_msg); 00051 00052 virtual void addPoint(float x, float y, float z, uint16_t ring, uint16_t azimuth, float distance, float intensity); 00053 00054 sensor_msgs::PointCloud2Iterator<float> iter_x, iter_y, iter_z, iter_intensity; 00055 sensor_msgs::PointCloud2Iterator<uint16_t> iter_ring; 00056 }; 00057 } // namespace velodyne_pointcloud 00058 00059 #endif // VELODYNE_POINTCLOUD_POINTCLOUDXYZIR_H