00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #ifndef PCL_POINT_CLOUD_H_
00039 #define PCL_POINT_CLOUD_H_
00040
00041 #include <Eigen/StdVector>
00042 #include <Eigen/Geometry>
00043 #include "pcl/ros_macros.h"
00044 #if ROS_VERSION_MINIMUM(1, 3, 0)
00045 #include <std_msgs/Header.h>
00046 #else
00047 #include <roslib/Header.h>
00048 #endif
00049 #include <pcl/exceptions.h>
00050 #include <boost/shared_ptr.hpp>
00051 #include <boost/make_shared.hpp>
00052
00053 namespace pcl
00054 {
00055 namespace detail
00056 {
00057 struct FieldMapping
00058 {
00059 size_t serialized_offset;
00060 size_t struct_offset;
00061 size_t size;
00062 };
00063 }
00064
00065 typedef std::vector<detail::FieldMapping> MsgFieldMap;
00066
00067
00068 template <typename PointT> class PointCloud;
00069
00070 namespace detail
00071 {
00072 template <typename PointT>
00073 boost::shared_ptr<pcl::MsgFieldMap>& getMapping(pcl::PointCloud<PointT>& p);
00074 }
00075
00079 template <typename PointT>
00080 class PointCloud
00081 {
00082 public:
00083 PointCloud () : width (0), height (0), is_dense (true),
00084 sensor_origin_ (Eigen::Vector4f::Zero ()), sensor_orientation_ (Eigen::Quaternionf::Identity ())
00085 {}
00086
00088 inline PointCloud& operator = (const PointCloud& rhs)
00089 {
00090 header = rhs.header;
00091 points = rhs.points;
00092 width = rhs.width;
00093 height = rhs.height;
00094 sensor_origin_ = rhs.sensor_origin_;
00095 sensor_orientation_ = rhs.sensor_orientation_;
00096 is_dense = rhs.is_dense;
00097 return (*this);
00098 }
00099
00101 inline PointCloud& operator += (const PointCloud& rhs)
00102 {
00103 if (rhs.header.frame_id != header.frame_id)
00104 {
00105 ROS_ERROR ("PointCloud frame IDs do not match (%s != %s) for += . Cancelling operation...",
00106 rhs.header.frame_id.c_str (), header.frame_id.c_str ());
00107 return (*this);
00108 }
00109
00110
00111 if (rhs.header.stamp > header.stamp)
00112 header.stamp = rhs.header.stamp;
00113
00114 size_t nr_points = points.size ();
00115 points.resize (nr_points + rhs.points.size ());
00116 for (size_t i = nr_points; i < points.size (); ++i)
00117 points[i] = rhs.points[i - nr_points];
00118
00119 width = points.size ();
00120 height = 1;
00121 if (rhs.is_dense && is_dense)
00122 is_dense = true;
00123 else
00124 is_dense = false;
00125 return (*this);
00126 }
00127
00129 inline PointT at (int u, int v) const
00130 {
00131 if (this->height > 1)
00132 return (points.at (v * this->width + u));
00133 else
00134 throw IsNotDenseException ("Can't use 2D indexing with a sparse point cloud");
00135 }
00136
00138 inline const PointT& operator () (int u, int v) const
00139 {
00140 return (points[v * this->width + u]);
00141 }
00142
00143 inline PointT& operator () (int u, int v)
00144 {
00145 return (points[v * this->width + u]);
00146 }
00147
00150 #if ROS_VERSION_MINIMUM(1, 3, 0)
00151 std_msgs::Header header;
00152 #else
00153 roslib::Header header;
00154 #endif
00155
00157 std::vector<PointT, Eigen::aligned_allocator<PointT> > points;
00158
00160 uint32_t width;
00162 uint32_t height;
00163
00165 bool is_dense;
00166
00168 Eigen::Vector4f sensor_origin_;
00170 Eigen::Quaternionf sensor_orientation_;
00171
00172 typedef PointT PointType;
00173 typedef std::vector<PointT, Eigen::aligned_allocator<PointT> > VectorType;
00174 typedef boost::shared_ptr<PointCloud<PointT> > Ptr;
00175 typedef boost::shared_ptr<const PointCloud<PointT> > ConstPtr;
00176
00177
00178 typedef typename VectorType::iterator iterator;
00179 typedef typename VectorType::const_iterator const_iterator;
00180 inline iterator begin () { return (points.begin ()); }
00181 inline iterator end () { return (points.end ()); }
00182 inline const_iterator begin () const { return (points.begin ()); }
00183 inline const_iterator end () const { return (points.end ()); }
00184
00185 inline size_t size () const { return (points.size ()); }
00186 inline void push_back (const PointT& p) { points.push_back (p); }
00187
00188
00189 inline Ptr makeShared () const { return Ptr (new PointCloud<PointT> (*this)); }
00190
00191 protected:
00192
00193 boost::shared_ptr<MsgFieldMap> mapping_;
00194
00195 friend boost::shared_ptr<MsgFieldMap>& detail::getMapping<PointT>(PointCloud& p);
00196
00197 public:
00198 EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
00199 };
00200
00201 namespace detail
00202 {
00203 template <typename PointT>
00204 boost::shared_ptr<pcl::MsgFieldMap>& getMapping(pcl::PointCloud<PointT>& p) { return p.mapping_; }
00205 }
00206
00207 template <typename PointT>
00208 std::ostream& operator << (std::ostream& s, const pcl::PointCloud<PointT> &p)
00209 {
00210 s << "header: " << std::endl;
00211 s << p.header;
00212 s << "points[]: " << p.points.size () << std::endl;
00213 s << "width: " << p.width << std::endl;
00214 s << "height: " << p.height << std::endl;
00215 s << "sensor_origin_: "
00216 << p.sensor_origin_[0] << ' '
00217 << p.sensor_origin_[1] << ' '
00218 << p.sensor_origin_[2] << std::endl;
00219 s << "sensor_orientation_: "
00220 << p.sensor_orientation_.x() << ' '
00221 << p.sensor_orientation_.y() << ' '
00222 << p.sensor_orientation_.z() << ' '
00223 << p.sensor_orientation_.w() << std::endl;
00224 s << "is_dense: " << p.is_dense << std::endl;
00225 return (s);
00226 }
00227 }
00228
00229 #endif //#ifndef PCL_POINT_CLOUD_H_