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 namespace pcl
00039 {
00041
00042 template<typename PointInT, typename PointOutT>
00043 struct NdConcatenateFunctor
00044 {
00045 typedef typename traits::POD<PointInT>::type PodIn;
00046 typedef typename traits::POD<PointOutT>::type PodOut;
00047
00048 NdConcatenateFunctor (const PointInT &p1, PointOutT &p2)
00049 : p1_ (reinterpret_cast<const PodIn&>(p1)), p2_ (reinterpret_cast<PodOut&>(p2)) { }
00050
00051 template<typename Key> inline void operator() ()
00052 {
00053
00054
00055 typedef typename pcl::traits::datatype<PointInT, Key>::type InT;
00056 typedef typename pcl::traits::datatype<PointOutT, Key>::type OutT;
00057
00058 BOOST_MPL_ASSERT_MSG((boost::is_same<InT, OutT>::value),
00059 POINT_IN_AND_POINT_OUT_HAVE_DIFFERENT_TYPES_FOR_FIELD,
00060 (Key, PointInT, InT, PointOutT, OutT));
00061 memcpy(reinterpret_cast<uint8_t*>(&p2_) + pcl::traits::offset<PointOutT, Key>::value,
00062 reinterpret_cast<const uint8_t*>(&p1_) + pcl::traits::offset<PointInT, Key>::value,
00063 sizeof(InT));
00064 }
00065
00066 private:
00067 const PodIn &p1_;
00068 PodOut &p2_;
00069 };
00070 }
00071
00073 template <typename PointT> int
00074 pcl::getFieldIndex (const pcl::PointCloud<PointT> &cloud, const std::string &field_name, std::vector<sensor_msgs::PointField> &fields)
00075 {
00076 fields.clear ();
00077
00078 pcl::for_each_type<typename pcl::traits::fieldList<PointT>::type>(pcl::detail::FieldAdder<PointT>(fields));
00079 for (size_t d = 0; d < fields.size (); ++d)
00080 if (fields[d].name == field_name)
00081 return (d);
00082 return (-1);
00083 }
00084
00086 template <typename PointT> void
00087 pcl::getFields (const pcl::PointCloud<PointT> &cloud, std::vector<sensor_msgs::PointField> &fields)
00088 {
00089 fields.clear ();
00090
00091 pcl::for_each_type<typename pcl::traits::fieldList<PointT>::type>(pcl::detail::FieldAdder<PointT>(fields));
00092 }
00093
00095 template <typename PointT> std::string
00096 pcl::getFieldsList (const pcl::PointCloud<PointT> &cloud)
00097 {
00098
00099 std::vector<sensor_msgs::PointField> fields;
00100 pcl::for_each_type<typename pcl::traits::fieldList<PointT>::type>(pcl::detail::FieldAdder<PointT>(fields));
00101 std::string result;
00102 for (size_t i = 0; i < fields.size () - 1; ++i)
00103 result += fields[i].name + " ";
00104 result += fields[fields.size () - 1].name;
00105 return (result);
00106 }
00107
00109 template <typename PointInT, typename PointOutT> void
00110 pcl::copyPointCloud (const pcl::PointCloud<PointInT> &cloud_in, pcl::PointCloud<PointOutT> &cloud_out)
00111 {
00112
00113 cloud_out.points.resize (cloud_in.points.size ());
00114 cloud_out.header = cloud_in.header;
00115 cloud_out.width = cloud_in.points.size ();
00116 cloud_out.height = 1;
00117 cloud_out.is_dense = cloud_in.is_dense;
00118
00119
00120 typedef typename pcl::traits::fieldList<PointInT>::type FieldList;
00121
00122 for (size_t i = 0; i < cloud_in.points.size (); ++i)
00123
00124 pcl::for_each_type <FieldList> (pcl::NdConcatenateFunctor <PointInT, PointOutT> (cloud_in.points[i], cloud_out.points[i]));
00125 }
00126
00128 template <typename PointT> void
00129 pcl::copyPointCloud (const pcl::PointCloud<PointT> &cloud_in, const std::vector<int> &indices,
00130 pcl::PointCloud<PointT> &cloud_out)
00131 {
00132
00133 cloud_out.points.resize (indices.size ());
00134 cloud_out.header = cloud_in.header;
00135 cloud_out.width = indices.size ();
00136 cloud_out.height = 1;
00137 if (cloud_in.is_dense)
00138 cloud_out.is_dense = true;
00139 else
00140
00141
00142 cloud_out.is_dense = false;
00143
00144
00145 typedef typename pcl::traits::fieldList<PointT>::type FieldList;
00146
00147 for (size_t i = 0; i < indices.size (); ++i)
00148
00149 pcl::for_each_type <FieldList> (pcl::NdConcatenateFunctor <PointT, PointT> (cloud_in.points[indices[i]], cloud_out.points[i]));
00150 }
00151
00153 template <typename PointT> void
00154 pcl::copyPointCloud (const pcl::PointCloud<PointT> &cloud_in, const pcl::PointIndices &indices,
00155 pcl::PointCloud<PointT> &cloud_out)
00156 {
00157
00158 cloud_out.points.resize (indices.indices.size ());
00159 cloud_out.header = cloud_in.header;
00160 cloud_out.width = indices.indices.size ();
00161 cloud_out.height = 1;
00162 if (cloud_in.is_dense)
00163 cloud_out.is_dense = true;
00164 else
00165
00166
00167 cloud_out.is_dense = false;
00168
00169
00170 typedef typename pcl::traits::fieldList<PointT>::type FieldList;
00171
00172 for (size_t i = 0; i < indices.indices.size (); ++i)
00173
00174 pcl::for_each_type <FieldList> (pcl::NdConcatenateFunctor <PointT, PointT> (cloud_in.points[indices.indices[i]], cloud_out.points[i]));
00175 }
00176
00178 template <typename PointT> void
00179 pcl::copyPointCloud (const pcl::PointCloud<PointT> &cloud_in, const std::vector<pcl::PointIndices> &indices,
00180 pcl::PointCloud<PointT> &cloud_out)
00181 {
00182 int nr_p = 0;
00183 for (size_t i = 0; i < indices.size (); ++i)
00184 nr_p += indices[i].indices.size ();
00185
00186
00187 cloud_out.points.resize (nr_p);
00188 cloud_out.header = cloud_in.header;
00189 cloud_out.width = nr_p;
00190 cloud_out.height = 1;
00191 if (cloud_in.is_dense)
00192 cloud_out.is_dense = true;
00193 else
00194
00195
00196 cloud_out.is_dense = false;
00197
00198
00199 typedef typename pcl::traits::fieldList<PointT>::type FieldList;
00200
00201 int cp = 0;
00202 for (size_t cc = 0; cc < indices.size (); ++cc)
00203 {
00204
00205 for (size_t i = 0; i < indices[cc].indices.size (); ++i)
00206 {
00207
00208 pcl::for_each_type <FieldList> (pcl::NdConcatenateFunctor <PointT, PointT> (cloud_in.points[indices[cc].indices[i]], cloud_out.points[cp]));
00209 cp++;
00210 }
00211 }
00212 }
00213
00215 template <typename PointIn1T, typename PointIn2T, typename PointOutT> void
00216 pcl::concatenateFields (const pcl::PointCloud<PointIn1T> &cloud1_in,
00217 const pcl::PointCloud<PointIn2T> &cloud2_in,
00218 pcl::PointCloud<PointOutT> &cloud_out)
00219 {
00220 typedef typename pcl::traits::fieldList<PointIn1T>::type FieldList1;
00221 typedef typename pcl::traits::fieldList<PointIn2T>::type FieldList2;
00222
00223 if (cloud1_in.points.size () != cloud2_in.points.size ())
00224 {
00225 ROS_ERROR ("[pcl::concatenateFields] The number of points in the two input datasets differs!");
00226 return;
00227 }
00228
00229
00230 cloud_out.points.resize (cloud1_in.points.size ());
00231 cloud_out.header = cloud1_in.header;
00232 cloud_out.width = cloud1_in.width;
00233 cloud_out.height = cloud1_in.height;
00234 if (!cloud1_in.is_dense || !cloud2_in.is_dense)
00235 cloud_out.is_dense = false;
00236 else
00237 cloud_out.is_dense = true;
00238
00239
00240 for (size_t i = 0; i < cloud_out.points.size (); ++i)
00241 {
00242
00243 pcl::for_each_type <FieldList1> (pcl::NdConcatenateFunctor <PointIn1T, PointOutT> (cloud1_in.points[i], cloud_out.points[i]));
00244 pcl::for_each_type <FieldList2> (pcl::NdConcatenateFunctor <PointIn2T, PointOutT> (cloud2_in.points[i], cloud_out.points[i]));
00245 }
00246 }