datacontainerbase.h
Go to the documentation of this file.
00001 #ifndef VELODYNE_POINTCLOUD_DATACONTAINERBASE_H
00002 #define VELODYNE_POINTCLOUD_DATACONTAINERBASE_H
00003 // Copyright (C) 2012, 2019 Austin Robot Technology, Jack O'Quin, Joshua Whitley, Sebastian Pütz
00004 // All rights reserved.
00005 //
00006 // Software License Agreement (BSD License 2.0)
00007 //
00008 // Redistribution and use in source and binary forms, with or without
00009 // modification, are permitted provided that the following conditions
00010 // are met:
00011 //
00012 //  * Redistributions of source code must retain the above copyright
00013 //    notice, this list of conditions and the following disclaimer.
00014 //  * Redistributions in binary form must reproduce the above
00015 //    copyright notice, this list of conditions and the following
00016 //    disclaimer in the documentation and/or other materials provided
00017 //    with the distribution.
00018 //  * Neither the name of {copyright_holder} nor the names of its
00019 //    contributors may be used to endorse or promote products derived
00020 //    from this software without specific prior written permission.
00021 //
00022 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 // COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 // INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 // BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 // POSSIBILITY OF SUCH DAMAGE.
00034 
00035 #include <tf/transform_listener.h>
00036 #include <velodyne_msgs/VelodyneScan.h>
00037 #include <sensor_msgs/point_cloud2_iterator.h>
00038 #include <Eigen/Dense>
00039 #include <string>
00040 #include <algorithm>
00041 #include <cstdarg>
00042 
00043 namespace velodyne_rawdata
00044 {
00045 class DataContainerBase
00046 {
00047 public:
00048   DataContainerBase(const double max_range, const double min_range, const std::string& target_frame,
00049                     const std::string& fixed_frame, const unsigned int init_width, const unsigned int init_height,
00050                     const bool is_dense, const unsigned int scans_per_packet,
00051                     boost::shared_ptr<tf::TransformListener>& tf_ptr, int fields, ...)
00052     : config_(max_range, min_range, target_frame, fixed_frame, init_width, init_height, is_dense, scans_per_packet)
00053     , tf_ptr(tf_ptr)
00054   {
00055     va_list vl;
00056     cloud.fields.clear();
00057     cloud.fields.reserve(fields);
00058     va_start(vl, fields);
00059     int offset = 0;
00060     for (int i = 0; i < fields; ++i)
00061     {
00062       // Create the corresponding PointField
00063       std::string name(va_arg(vl, char*));
00064       int count(va_arg(vl, int));
00065       int datatype(va_arg(vl, int));
00066       offset = addPointField(cloud, name, count, datatype, offset);
00067     }
00068     va_end(vl);
00069     cloud.point_step = offset;
00070     cloud.row_step = init_width * cloud.point_step;
00071     if (config_.transform && !tf_ptr)
00072     {
00073       tf_ptr = boost::shared_ptr<tf::TransformListener>(new tf::TransformListener);
00074     }
00075   }
00076 
00077   struct Config
00078   {
00079     double max_range;          
00080     double min_range;          
00081     std::string target_frame;  
00082     std::string fixed_frame;   
00083     unsigned int init_width;
00084     unsigned int init_height;
00085     bool is_dense;
00086     unsigned int scans_per_packet;
00087     bool transform;  
00088 
00089     Config(double max_range, double min_range, std::string target_frame, std::string fixed_frame,
00090            unsigned int init_width, unsigned int init_height, bool is_dense, unsigned int scans_per_packet)
00091       : max_range(max_range)
00092       , min_range(min_range)
00093       , target_frame(target_frame)
00094       , fixed_frame(fixed_frame)
00095       , transform(fixed_frame != target_frame)
00096       , init_width(init_width)
00097       , init_height(init_height)
00098       , is_dense(is_dense)
00099       , scans_per_packet(scans_per_packet)
00100     {
00101       ROS_INFO_STREAM("Initialized container with "
00102                       << "min_range: " << min_range << ", max_range: " << max_range
00103                       << ", target_frame: " << target_frame << ", fixed_frame: " << fixed_frame
00104                       << ", init_with: " << init_width << ", init_height: " << init_height << ", is_dense: " << is_dense
00105                       << ", scans_per_packet: " << scans_per_packet);
00106     }
00107   };
00108 
00109   virtual void setup(const velodyne_msgs::VelodyneScan::ConstPtr& scan_msg)
00110   {
00111     cloud.header = scan_msg->header;
00112     cloud.data.resize(scan_msg->packets.size() * config_.scans_per_packet * cloud.point_step);
00113     cloud.width = config_.init_width;
00114     cloud.height = config_.init_height;
00115     cloud.is_dense = static_cast<uint8_t>(config_.is_dense);
00116   }
00117 
00118   virtual void addPoint(float x, float y, float z, const uint16_t ring, const uint16_t azimuth, const float distance,
00119                         const float intensity) = 0;
00120   virtual void newLine() = 0;
00121 
00122   const sensor_msgs::PointCloud2& finishCloud()
00123   {
00124     cloud.data.resize(cloud.point_step * cloud.width * cloud.height);
00125 
00126     if (!config_.target_frame.empty())
00127     {
00128       cloud.header.frame_id = config_.target_frame;
00129     }
00130 
00131     ROS_DEBUG_STREAM("Prepared cloud width" << cloud.height * cloud.width
00132                                             << " Velodyne points, time: " << cloud.header.stamp);
00133     return cloud;
00134   }
00135 
00136   void configure(const double max_range, const double min_range, const std::string fixed_frame,
00137                  const std::string target_frame)
00138   {
00139     config_.max_range = max_range;
00140     config_.min_range = min_range;
00141     config_.fixed_frame = fixed_frame;
00142     config_.target_frame = target_frame;
00143 
00144     config_.transform = fixed_frame.compare(target_frame) != 0;
00145     if (config_.transform && !tf_ptr)
00146     {
00147       tf_ptr = boost::shared_ptr<tf::TransformListener>(new tf::TransformListener);
00148     }
00149   }
00150 
00151   sensor_msgs::PointCloud2 cloud;
00152 
00153   inline void vectorTfToEigen(tf::Vector3& tf_vec, Eigen::Vector3f& eigen_vec)
00154   {
00155     eigen_vec(0) = tf_vec[0];
00156     eigen_vec(1) = tf_vec[1];
00157     eigen_vec(2) = tf_vec[2];
00158   }
00159 
00160   inline bool computeTransformation(const ros::Time& time)
00161   {
00162     tf::StampedTransform transform;
00163     try
00164     {
00165       tf_ptr->lookupTransform(config_.target_frame, cloud.header.frame_id, time, transform);
00166     }
00167     catch (tf::LookupException& e)
00168     {
00169       ROS_ERROR("%s", e.what());
00170       return false;
00171     }
00172     catch (tf::ExtrapolationException& e)
00173     {
00174       ROS_ERROR("%s", e.what());
00175       return false;
00176     }
00177 
00178     tf::Quaternion quaternion = transform.getRotation();
00179     Eigen::Quaternionf rotation(quaternion.w(), quaternion.x(), quaternion.y(), quaternion.z());
00180 
00181     Eigen::Vector3f eigen_origin;
00182     vectorTfToEigen(transform.getOrigin(), eigen_origin);
00183     Eigen::Translation3f translation(eigen_origin);
00184     transformation = translation * rotation;
00185     return true;
00186   }
00187 
00188   inline void transformPoint(float& x, float& y, float& z)
00189   {
00190     Eigen::Vector3f p = transformation * Eigen::Vector3f(x, y, z);
00191     x = p.x();
00192     y = p.y();
00193     z = p.z();
00194   }
00195 
00196   inline bool pointInRange(float range)
00197   {
00198     return (range >= config_.min_range && range <= config_.max_range);
00199   }
00200 
00201 protected:
00202   Config config_;
00203   boost::shared_ptr<tf::TransformListener> tf_ptr;  
00204   Eigen::Affine3f transformation;
00205 };
00206 } /* namespace velodyne_rawdata */
00207 #endif  // VELODYNE_POINTCLOUD_DATACONTAINERBASE_H


velodyne_pointcloud
Author(s): Jack O'Quin, Piyush Khandelwal, Jesse Vera, Sebastian Pütz
autogenerated on Wed Jul 3 2019 19:32:23