Hi Yohei, I am not sure what exactly do you mean by "recommended/correct way" but in case of TUM we normally define new types on per package base, e.g. for our "pcl_cloud_alogs" package we simply have definitions in "pcl_cloud_algos_point_types.h and pcl_cloud_algos_point_types.hpp" files and just use them as every other point type defined in pcl. D. On Tue, Jan 25, 2011 at 4:23 AM, Yohei Kakiuchi wrote: > I confirmed that a user-defined point type described in > http://www.ros.org/wiki/pcl_ros worked well for our purpose. > > I have a question for using a user-defined point type. > PointXYZRGB defined in point_types.hpp is using PCL_ADD_POINT4D, > EIGEN_ALIGNE16. > I tested simple user-defined class not using EIGEN_ALIGN16 and > a user-defined class added 'category' to PointXYZRGB. > Both classes worked well. > Which is the recommended / correct way for using a user-defined class? > > * test code > > --- > namespace my_ns > { > #if 0 >  struct PointXYZRGBClass >  { >   float x; >   float y; >   float z; >   float rgb; >   uint32_t category; >  }; > #else >  struct PointXYZRGBClass >  { >    PCL_ADD_POINT4D;  // This adds the members x,y,z which can also be > accessed using the point (which is float[4]) >    float rgb; >    uint32_t category; >    EIGEN_MAKE_ALIGNED_OPERATOR_NEW >  } EIGEN_ALIGN16; > #endif > } // namespace my_ns > > POINT_CLOUD_REGISTER_POINT_STRUCT > (my_ns::PointXYZRGBClass, >  (float, x, x) >  (float, y, y) >  (float, z, z) >  (float, rgb, rgb) >  (uint32_t, category, category) >  ); > > 2011/1/24 Kei Okada : >>> Frequently, these problems are better solved by republishing some or >>> all of the original points as a single PointCloud2 with a >>> categorization field. The data can be sorted on that field for >>> efficient access, sometimes that occurs naturally as a result of your >>> algorithm, anyway. >> >> I see, that's seems good solution. >> >> Just to be clear, your suggestion is to make PointCloud2 data as followings. >>    sensor_msgs::PointCloud2 cloud2_; >>    cloud2_.fields.resize( 5 ); >>    cloud2_.fields[0].name = "x"; >>    cloud2_.fields[1].name = "y"; >>    cloud2_.fields[2].name = "z"; >>    cloud2_.fields[3].name = "rgb"; >>    cloud2_.fields[3].name = "label" or "category"; >> if this is correct, is there a way to convert from/to pcl::Point*** ?? >> Usually, we will write program using pcll:PointCloud... >> >> >> On Sun, Jan 23, 2011 at 2:43 AM, Jack O'Quin wrote: >>> On Fri, Jan 21, 2011 at 7:32 AM, cmuell2s >>> wrote: >>>> Hello all, >>>> >>>> I stuck at a small problem. I would like to publish a vector/array of >>>> pcl::PointCloud. >>>> I couldn't find a sensor_msg or std_msg which would do it, did I >>>> overlooked sth? >>> >>> This comes up frequently. In many cases it seems the obvious solution. >>> >>> Often, problems become apparent on further consideration: who will >>> read this vector of pointclouds? What operations must be performed on >>> it? >>> >>> Frequently, these problems are better solved by republishing some or >>> all of the original points as a single PointCloud2 with a >>> categorization field. The data can be sorted on that field for >>> efficient access, sometimes that occurs naturally as a result of your >>> algorithm, anyway. >>> -- >>>  joq >>> _______________________________________________ >>> ros-users mailing list >>> ros-users@code.ros.org >>> https://code.ros.org/mailman/listinfo/ros-users >>> >> _______________________________________________ >> ros-users mailing list >> ros-users@code.ros.org >> https://code.ros.org/mailman/listinfo/ros-users >> > _______________________________________________ > ros-users mailing list > ros-users@code.ros.org > https://code.ros.org/mailman/listinfo/ros-users > -- MSc. Dejan Pangercic PhD Student/Researcher Intelligent Autonomous Systems Group Technische Universität München Telephone: +49 (89) 289-26908 E-Mail: dejan.pangercic@cs.tum.edu WWW: http://ias.cs.tum.edu/people/pangercic