2013-06-26 15:41:31 -07:00
/*
* Software License Agreement ( BSD License )
*
* Copyright ( c ) 2013 , Open Source Robotics Foundation , Inc .
* All rights reserved .
*
* Redistribution and use in source and binary forms , with or without
* modification , are permitted provided that the following conditions
* are met :
*
* * Redistributions of source code must retain the above copyright
* notice , this list of conditions and the following disclaimer .
* * Redistributions in binary form must reproduce the above
* copyright notice , this list of conditions and the following
* disclaimer in the documentation and / or other materials provided
* with the distribution .
* * Neither the name of Open Source Robotics Foundation , Inc . nor
* the names of its contributors may be used to endorse or promote
* products derived from this software without specific prior
* written permission .
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* " AS IS " AND ANY EXPRESS OR IMPLIED WARRANTIES , INCLUDING , BUT NOT
* LIMITED TO , THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED . IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT , INDIRECT ,
* INCIDENTAL , SPECIAL , EXEMPLARY , OR CONSEQUENTIAL DAMAGES ( INCLUDING ,
* BUT NOT LIMITED TO , PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES ;
* LOSS OF USE , DATA , OR PROFITS ; OR BUSINESS INTERRUPTION ) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY , WHETHER IN CONTRACT , STRICT
* LIABILITY , OR TORT ( INCLUDING NEGLIGENCE OR OTHERWISE ) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE , EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE .
*/
2013-07-08 16:29:37 -07:00
# ifndef PCL_CONVERSIONS_H__
# define PCL_CONVERSIONS_H__
2013-06-26 15:41:31 -07:00
# include <vector>
2013-07-08 16:32:39 -07:00
# include <ros/ros.h>
# include <pcl/conversions.h>
# include <pcl/PCLHeader.h>
2013-06-26 15:41:31 -07:00
# include <std_msgs/Header.h>
2013-07-08 16:32:39 -07:00
# include <pcl/PCLImage.h>
2013-06-26 15:41:31 -07:00
# include <sensor_msgs/Image.h>
2013-07-08 16:32:39 -07:00
# include <pcl/PCLPointField.h>
2013-06-26 15:41:31 -07:00
# include <sensor_msgs/PointField.h>
2013-07-08 16:32:39 -07:00
# include <pcl/PCLPointCloud2.h>
2013-06-26 15:41:31 -07:00
# include <sensor_msgs/PointCloud2.h>
2013-07-08 17:36:58 -07:00
# include <pcl/PointIndices.h>
# include <pcl_msgs/PointIndices.h>
2013-07-09 18:55:42 -07:00
# include <pcl/ModelCoefficients.h>
# include <pcl_msgs/ModelCoefficients.h>
# include <pcl/Vertices.h>
# include <pcl_msgs/Vertices.h>
# include <pcl/PolygonMesh.h>
# include <pcl_msgs/PolygonMesh.h>
2013-07-08 16:34:15 -07:00
# include <pcl/io/pcd_io.h>
# include <Eigen/StdVector>
# include <Eigen/Geometry>
2013-06-26 15:41:31 -07:00
namespace pcl_conversions {
2013-07-09 18:55:42 -07:00
/** PCLHeader <=> Header **/
2013-06-26 15:41:31 -07:00
2013-07-09 18:55:42 -07:00
inline
void fromPCL ( const pcl : : PCLHeader & pcl_header , std_msgs : : Header & header )
{
2013-06-26 15:45:02 -07:00
header . stamp . fromNSec ( pcl_header . stamp * 1e3 ) ; // Convert from us to ns
2013-06-26 15:41:31 -07:00
header . seq = pcl_header . seq ;
header . frame_id = pcl_header . frame_id ;
2013-07-09 18:55:42 -07:00
}
2013-06-26 15:41:31 -07:00
2013-07-09 18:55:42 -07:00
inline
void toPCL ( const std_msgs : : Header & header , pcl : : PCLHeader & pcl_header )
{
2013-06-26 15:45:02 -07:00
pcl_header . stamp = header . stamp . toNSec ( ) / 1e3 ; // Convert from ns to us
2013-06-26 15:41:31 -07:00
pcl_header . seq = header . seq ;
pcl_header . frame_id = header . frame_id ;
2013-07-09 18:55:42 -07:00
}
2013-06-26 15:41:31 -07:00
2013-07-09 18:55:42 -07:00
inline
std_msgs : : Header fromPCL ( const pcl : : PCLHeader & pcl_header )
{
2013-07-08 16:33:56 -07:00
std_msgs : : Header header ;
fromPCL ( pcl_header , header ) ;
return header ;
2013-07-09 18:55:42 -07:00
}
2013-07-08 16:33:56 -07:00
2013-07-09 18:55:42 -07:00
inline
pcl : : PCLHeader toPCL ( const std_msgs : : Header & header )
{
2013-07-08 16:33:56 -07:00
pcl : : PCLHeader pcl_header ;
toPCL ( header , pcl_header ) ;
return pcl_header ;
2013-07-09 18:55:42 -07:00
}
2013-07-08 16:33:56 -07:00
2013-07-09 18:55:42 -07:00
/** PCLImage <=> Image **/
2013-06-26 15:41:31 -07:00
2013-07-09 18:55:42 -07:00
inline
void copyPCLImageMetaData ( const pcl : : PCLImage & pcl_image , sensor_msgs : : Image & image )
{
2013-06-28 12:07:30 -07:00
fromPCL ( pcl_image . header , image . header ) ;
2013-06-26 15:41:31 -07:00
image . height = pcl_image . height ;
image . width = pcl_image . width ;
image . encoding = pcl_image . encoding ;
image . is_bigendian = pcl_image . is_bigendian ;
image . step = pcl_image . step ;
2013-07-09 18:55:42 -07:00
}
inline
void fromPCL ( const pcl : : PCLImage & pcl_image , sensor_msgs : : Image & image )
{
copyPCLImageMetaData ( pcl_image , image ) ;
2013-06-26 15:41:31 -07:00
image . data = pcl_image . data ;
2013-07-09 18:55:42 -07:00
}
2013-06-26 15:41:31 -07:00
2013-07-09 18:55:42 -07:00
inline
void moveFromPCL ( pcl : : PCLImage & pcl_image , sensor_msgs : : Image & image )
{
copyPCLImageMetaData ( pcl_image , image ) ;
image . data . swap ( pcl_image . data ) ;
}
inline
void copyImageMetaData ( const sensor_msgs : : Image & image , pcl : : PCLImage & pcl_image )
{
2013-06-28 12:07:30 -07:00
toPCL ( image . header , pcl_image . header ) ;
2013-06-26 15:41:31 -07:00
pcl_image . height = image . height ;
pcl_image . width = image . width ;
pcl_image . encoding = image . encoding ;
pcl_image . is_bigendian = image . is_bigendian ;
pcl_image . step = image . step ;
2013-07-09 18:55:42 -07:00
}
inline
void toPCL ( const sensor_msgs : : Image & image , pcl : : PCLImage & pcl_image )
{
copyImageMetaData ( image , pcl_image ) ;
2013-06-26 15:41:31 -07:00
pcl_image . data = image . data ;
2013-07-09 18:55:42 -07:00
}
2013-06-26 15:41:31 -07:00
2013-07-09 18:55:42 -07:00
inline
void moveToPCL ( sensor_msgs : : Image & image , pcl : : PCLImage & pcl_image )
{
copyImageMetaData ( image , pcl_image ) ;
pcl_image . data . swap ( image . data ) ;
}
2013-06-26 15:41:31 -07:00
2013-07-09 18:55:42 -07:00
/** PCLPointField <=> PointField **/
inline
void fromPCL ( const pcl : : PCLPointField & pcl_pf , sensor_msgs : : PointField & pf )
{
2013-06-26 15:41:31 -07:00
pf . name = pcl_pf . name ;
pf . offset = pcl_pf . offset ;
pf . datatype = pcl_pf . datatype ;
pf . count = pcl_pf . count ;
2013-07-09 18:55:42 -07:00
}
2013-06-26 15:41:31 -07:00
2013-07-09 18:55:42 -07:00
inline
void fromPCL ( const std : : vector < pcl : : PCLPointField > & pcl_pfs , std : : vector < sensor_msgs : : PointField > & pfs )
{
2013-07-08 16:33:56 -07:00
pfs . resize ( pcl_pfs . size ( ) ) ;
std : : vector < pcl : : PCLPointField > : : const_iterator it = pcl_pfs . begin ( ) ;
int i = 0 ;
for ( ; it ! = pcl_pfs . end ( ) ; + + it , + + i ) {
2013-07-09 18:55:42 -07:00
fromPCL ( * ( it ) , pfs [ i ] ) ;
2013-07-08 16:33:56 -07:00
}
2013-07-09 18:55:42 -07:00
}
2013-07-08 16:33:56 -07:00
2013-07-09 18:55:42 -07:00
inline
void toPCL ( const sensor_msgs : : PointField & pf , pcl : : PCLPointField & pcl_pf )
{
2013-06-26 15:41:31 -07:00
pcl_pf . name = pf . name ;
pcl_pf . offset = pf . offset ;
pcl_pf . datatype = pf . datatype ;
pcl_pf . count = pf . count ;
2013-07-09 18:55:42 -07:00
}
2013-06-26 15:41:31 -07:00
2013-07-09 18:55:42 -07:00
inline
void toPCL ( const std : : vector < sensor_msgs : : PointField > & pfs , std : : vector < pcl : : PCLPointField > & pcl_pfs )
{
2013-07-08 16:33:56 -07:00
pcl_pfs . resize ( pfs . size ( ) ) ;
std : : vector < sensor_msgs : : PointField > : : const_iterator it = pfs . begin ( ) ;
int i = 0 ;
for ( ; it ! = pfs . end ( ) ; + + it , + + i ) {
2013-07-09 18:55:42 -07:00
toPCL ( * ( it ) , pcl_pfs [ i ] ) ;
2013-07-08 16:33:56 -07:00
}
2013-07-09 18:55:42 -07:00
}
2013-07-08 16:33:56 -07:00
2013-07-09 18:55:42 -07:00
/** PCLPointCloud2 <=> PointCloud2 **/
2013-06-26 15:41:31 -07:00
2013-07-09 18:55:42 -07:00
inline
void copyPCLPointCloud2MetaData ( const pcl : : PCLPointCloud2 & pcl_pc2 , sensor_msgs : : PointCloud2 & pc2 )
{
2013-06-28 12:07:30 -07:00
fromPCL ( pcl_pc2 . header , pc2 . header ) ;
2013-06-26 15:41:31 -07:00
pc2 . height = pcl_pc2 . height ;
pc2 . width = pcl_pc2 . width ;
2013-07-08 16:33:56 -07:00
fromPCL ( pcl_pc2 . fields , pc2 . fields ) ;
2013-06-26 15:41:31 -07:00
pc2 . is_bigendian = pcl_pc2 . is_bigendian ;
pc2 . point_step = pcl_pc2 . point_step ;
pc2 . row_step = pcl_pc2 . row_step ;
pc2 . is_dense = pcl_pc2 . is_dense ;
2013-07-09 18:55:42 -07:00
}
2013-06-26 15:41:31 -07:00
2013-07-09 18:55:42 -07:00
inline
void fromPCL ( const pcl : : PCLPointCloud2 & pcl_pc2 , sensor_msgs : : PointCloud2 & pc2 )
{
copyPCLPointCloud2MetaData ( pcl_pc2 , pc2 ) ;
pc2 . data = pcl_pc2 . data ;
}
inline
void moveFromPCL ( pcl : : PCLPointCloud2 & pcl_pc2 , sensor_msgs : : PointCloud2 & pc2 )
{
copyPCLPointCloud2MetaData ( pcl_pc2 , pc2 ) ;
pc2 . data . swap ( pcl_pc2 . data ) ;
}
inline
void copyPointCloud2MetaData ( const sensor_msgs : : PointCloud2 & pc2 , pcl : : PCLPointCloud2 & pcl_pc2 )
{
2013-06-28 12:07:30 -07:00
toPCL ( pc2 . header , pcl_pc2 . header ) ;
2013-06-26 15:41:31 -07:00
pcl_pc2 . height = pc2 . height ;
pcl_pc2 . width = pc2 . width ;
2013-07-08 16:33:56 -07:00
toPCL ( pc2 . fields , pcl_pc2 . fields ) ;
2013-06-26 15:41:31 -07:00
pcl_pc2 . is_bigendian = pc2 . is_bigendian ;
pcl_pc2 . point_step = pc2 . point_step ;
pcl_pc2 . row_step = pc2 . row_step ;
pcl_pc2 . is_dense = pc2 . is_dense ;
2013-07-09 18:55:42 -07:00
}
inline
void toPCL ( const sensor_msgs : : PointCloud2 & pc2 , pcl : : PCLPointCloud2 & pcl_pc2 )
{
copyPointCloud2MetaData ( pc2 , pcl_pc2 ) ;
pcl_pc2 . data = pc2 . data ;
}
2013-06-26 15:41:31 -07:00
2013-07-09 18:55:42 -07:00
inline
void moveToPCL ( sensor_msgs : : PointCloud2 & pc2 , pcl : : PCLPointCloud2 & pcl_pc2 )
{
copyPointCloud2MetaData ( pc2 , pcl_pc2 ) ;
pcl_pc2 . data . swap ( pc2 . data ) ;
}
2013-07-08 18:50:55 -07:00
2013-07-09 18:55:42 -07:00
/** pcl::PointIndices <=> pcl_msgs::PointIndices **/
2013-07-08 17:36:58 -07:00
2013-07-09 18:55:42 -07:00
inline
void fromPCL ( const pcl : : PointIndices & pcl_pi , pcl_msgs : : PointIndices & pi )
{
fromPCL ( pcl_pi . header , pi . header ) ;
pi . indices = pcl_pi . indices ;
}
inline
void moveFromPCL ( pcl : : PointIndices & pcl_pi , pcl_msgs : : PointIndices & pi )
{
fromPCL ( pcl_pi . header , pi . header ) ;
pi . indices . swap ( pcl_pi . indices ) ;
}
inline
void toPCL ( const pcl_msgs : : PointIndices & pi , pcl : : PointIndices & pcl_pi )
{
toPCL ( pi . header , pcl_pi . header ) ;
pcl_pi . indices = pi . indices ;
}
inline
void moveToPCL ( pcl_msgs : : PointIndices & pi , pcl : : PointIndices & pcl_pi )
{
toPCL ( pi . header , pcl_pi . header ) ;
pcl_pi . indices . swap ( pi . indices ) ;
}
/** pcl::ModelCoefficients <=> pcl_msgs::ModelCoefficients **/
inline
void fromPCL ( const pcl : : ModelCoefficients & pcl_mc , pcl_msgs : : ModelCoefficients & mc )
{
fromPCL ( pcl_mc . header , mc . header ) ;
mc . values = pcl_mc . values ;
}
inline
void moveFromPCL ( pcl : : ModelCoefficients & pcl_mc , pcl_msgs : : ModelCoefficients & mc )
{
fromPCL ( pcl_mc . header , mc . header ) ;
mc . values . swap ( pcl_mc . values ) ;
}
inline
void toPCL ( const pcl_msgs : : ModelCoefficients & mc , pcl : : ModelCoefficients & pcl_mc )
{
toPCL ( mc . header , pcl_mc . header ) ;
pcl_mc . values = mc . values ;
}
inline
void moveToPCL ( pcl_msgs : : ModelCoefficients & mc , pcl : : ModelCoefficients & pcl_mc )
{
toPCL ( mc . header , pcl_mc . header ) ;
pcl_mc . values . swap ( mc . values ) ;
}
/** pcl::Vertices <=> pcl_msgs::Vertices **/
inline
void fromPCL ( const pcl : : Vertices & pcl_vert , pcl_msgs : : Vertices & vert )
{
vert . vertices = pcl_vert . vertices ;
}
inline
void fromPCL ( const std : : vector < pcl : : Vertices > & pcl_verts , std : : vector < pcl_msgs : : Vertices > & verts )
{
verts . resize ( pcl_verts . size ( ) ) ;
std : : vector < pcl : : Vertices > : : const_iterator it = pcl_verts . begin ( ) ;
std : : vector < pcl_msgs : : Vertices > : : iterator jt = verts . begin ( ) ;
for ( ; it ! = pcl_verts . end ( ) & & jt ! = verts . end ( ) ; + + it , + + jt ) {
fromPCL ( * ( it ) , * ( jt ) ) ;
}
}
inline
void moveFromPCL ( pcl : : Vertices & pcl_vert , pcl_msgs : : Vertices & vert )
{
vert . vertices . swap ( pcl_vert . vertices ) ;
}
inline
void fromPCL ( std : : vector < pcl : : Vertices > & pcl_verts , std : : vector < pcl_msgs : : Vertices > & verts )
{
verts . resize ( pcl_verts . size ( ) ) ;
std : : vector < pcl : : Vertices > : : iterator it = pcl_verts . begin ( ) ;
std : : vector < pcl_msgs : : Vertices > : : iterator jt = verts . begin ( ) ;
for ( ; it ! = pcl_verts . end ( ) & & jt ! = verts . end ( ) ; + + it , + + jt ) {
moveFromPCL ( * ( it ) , * ( jt ) ) ;
}
}
inline
void toPCL ( const pcl_msgs : : Vertices & vert , pcl : : Vertices & pcl_vert )
{
pcl_vert . vertices = vert . vertices ;
}
inline
void toPCL ( const std : : vector < pcl_msgs : : Vertices > & verts , std : : vector < pcl : : Vertices > & pcl_verts )
{
pcl_verts . resize ( verts . size ( ) ) ;
std : : vector < pcl_msgs : : Vertices > : : const_iterator it = verts . begin ( ) ;
std : : vector < pcl : : Vertices > : : iterator jt = pcl_verts . begin ( ) ;
for ( ; it ! = verts . end ( ) & & jt ! = pcl_verts . end ( ) ; + + it , + + jt ) {
toPCL ( * ( it ) , * ( jt ) ) ;
}
}
inline
void moveToPCL ( pcl_msgs : : Vertices & vert , pcl : : Vertices & pcl_vert )
{
pcl_vert . vertices . swap ( vert . vertices ) ;
}
inline
void moveToPCL ( std : : vector < pcl_msgs : : Vertices > & verts , std : : vector < pcl : : Vertices > & pcl_verts )
{
pcl_verts . resize ( verts . size ( ) ) ;
std : : vector < pcl_msgs : : Vertices > : : iterator it = verts . begin ( ) ;
std : : vector < pcl : : Vertices > : : iterator jt = pcl_verts . begin ( ) ;
for ( ; it ! = verts . end ( ) & & jt ! = pcl_verts . end ( ) ; + + it , + + jt ) {
moveToPCL ( * ( it ) , * ( jt ) ) ;
}
}
/** pcl::PolygonMesh <=> pcl_msgs::PolygonMesh **/
inline
void fromPCL ( const pcl : : PolygonMesh & pcl_mesh , pcl_msgs : : PolygonMesh & mesh )
{
fromPCL ( pcl_mesh . header , mesh . header ) ;
fromPCL ( pcl_mesh . cloud , mesh . cloud ) ;
fromPCL ( pcl_mesh . polygons , mesh . polygons ) ;
}
inline
void moveFromPCL ( pcl : : PolygonMesh & pcl_mesh , pcl_msgs : : PolygonMesh & mesh )
{
fromPCL ( pcl_mesh . header , mesh . header ) ;
moveFromPCL ( pcl_mesh . cloud , mesh . cloud ) ;
moveFromPCL ( pcl_mesh . cloud , mesh . cloud ) ;
}
inline
void toPCL ( const pcl_msgs : : PolygonMesh & mesh , pcl : : PolygonMesh & pcl_mesh )
{
toPCL ( mesh . header , pcl_mesh . header ) ;
toPCL ( mesh . cloud , pcl_mesh . cloud ) ;
toPCL ( mesh . polygons , pcl_mesh . polygons ) ;
}
inline
void moveToPCL ( pcl_msgs : : PolygonMesh & mesh , pcl : : PolygonMesh & pcl_mesh )
{
toPCL ( mesh . header , pcl_mesh . header ) ;
moveToPCL ( mesh . cloud , pcl_mesh . cloud ) ;
moveToPCL ( mesh . polygons , pcl_mesh . polygons ) ;
}
2013-07-08 17:36:58 -07:00
2013-06-26 15:41:31 -07:00
} // namespace pcl_conversions
2013-07-08 16:29:37 -07:00
2013-07-08 16:34:15 -07:00
namespace pcl {
2013-07-09 18:55:42 -07:00
/** Overload pcl::getFieldIndex **/
inline int getFieldIndex ( const sensor_msgs : : PointCloud2 & cloud , const std : : string & field_name )
{
2013-07-08 16:34:15 -07:00
// Get the index we need
for ( size_t d = 0 ; d < cloud . fields . size ( ) ; + + d ) {
2013-07-09 18:55:42 -07:00
if ( cloud . fields [ d ] . name = = field_name ) {
return ( static_cast < int > ( d ) ) ;
}
2013-07-08 16:34:15 -07:00
}
return ( - 1 ) ;
2013-07-09 18:55:42 -07:00
}
2013-07-08 16:34:15 -07:00
2013-07-09 18:55:42 -07:00
/** Overload pcl::getFieldsList **/
2013-07-08 16:34:15 -07:00
2013-07-09 18:55:42 -07:00
inline std : : string getFieldsList ( const sensor_msgs : : PointCloud2 & cloud )
{
2013-07-08 16:34:15 -07:00
std : : string result ;
for ( size_t i = 0 ; i < cloud . fields . size ( ) - 1 ; + + i ) {
2013-07-09 18:55:42 -07:00
result + = cloud . fields [ i ] . name + " " ;
2013-07-08 16:34:15 -07:00
}
result + = cloud . fields [ cloud . fields . size ( ) - 1 ] . name ;
return ( result ) ;
2013-07-09 18:55:42 -07:00
}
2013-07-08 16:34:15 -07:00
2013-07-09 18:55:42 -07:00
/** Provide pcl::toROSMsg **/
2013-07-08 18:50:55 -07:00
2013-07-09 18:55:42 -07:00
inline
void toROSMsg ( const sensor_msgs : : PointCloud2 & cloud , sensor_msgs : : Image & image )
{
2013-07-08 16:34:15 -07:00
pcl : : PCLPointCloud2 pcl_cloud ;
pcl_conversions : : toPCL ( cloud , pcl_cloud ) ;
pcl : : PCLImage pcl_image ;
pcl : : toPCLPointCloud2 ( pcl_cloud , pcl_image ) ;
2013-07-09 18:55:42 -07:00
pcl_conversions : : moveFromPCL ( pcl_image , image ) ;
}
2013-07-08 16:34:15 -07:00
2013-07-09 18:55:42 -07:00
inline
void moveToROSMsg ( sensor_msgs : : PointCloud2 & cloud , sensor_msgs : : Image & image )
{
pcl : : PCLPointCloud2 pcl_cloud ;
pcl_conversions : : moveToPCL ( cloud , pcl_cloud ) ;
pcl : : PCLImage pcl_image ;
pcl : : toPCLPointCloud2 ( pcl_cloud , pcl_image ) ;
pcl_conversions : : moveFromPCL ( pcl_image , image ) ;
}
2013-07-09 21:49:26 -07:00
/** Provide to/fromROSMsg for sensor_msgs::PointCloud2 <=> pcl::PointCloud<T> **/
template < typename T >
void toROSMsg ( const pcl : : PointCloud < T > & pcl_cloud , sensor_msgs : : PointCloud2 & cloud )
{
pcl : : PCLPointCloud2 pcl_pc2 ;
pcl : : toPCLPointCloud2 ( pcl_cloud , pcl_pc2 ) ;
pcl_conversions : : moveFromPCL ( pcl_pc2 , cloud ) ;
}
template < typename T >
void fromROSMsg ( const sensor_msgs : : PointCloud2 & cloud , pcl : : PointCloud < T > & pcl_cloud )
{
pcl : : PCLPointCloud2 pcl_pc2 ;
pcl_conversions : : toPCL ( cloud , pcl_pc2 ) ;
pcl : : toPCLPointCloud2 ( pcl_cloud , cloud ) ;
}
template < typename T >
void moveFromROSMsg ( sensor_msgs : : PointCloud2 & cloud , pcl : : PointCloud < T > & pcl_cloud )
{
pcl : : PCLPointCloud2 pcl_pc2 ;
pcl_conversions : : moveToPCL ( cloud , pcl_pc2 ) ;
pcl : : toPCLPointCloud2 ( pcl_cloud , cloud ) ;
}
2013-07-09 18:55:42 -07:00
/** Overload pcl::createMapping **/
2013-07-09 21:49:26 -07:00
2013-07-09 18:55:42 -07:00
template < typename PointT >
void createMapping ( const std : : vector < sensor_msgs : : PointField > & msg_fields , MsgFieldMap & field_map )
{
2013-07-08 16:34:15 -07:00
std : : vector < pcl : : PCLPointField > pcl_msg_fields ;
pcl_conversions : : toPCL ( msg_fields , pcl_msg_fields ) ;
return createMapping < PointT > ( pcl_msg_fields , field_map ) ;
2013-07-09 18:55:42 -07:00
}
2013-07-08 16:34:15 -07:00
2013-07-09 18:55:42 -07:00
namespace io {
2013-07-08 16:34:15 -07:00
2013-07-09 18:55:42 -07:00
/** Overload pcl::io::savePCDFile **/
2013-07-09 21:49:26 -07:00
2013-07-09 18:55:42 -07:00
inline int
savePCDFile ( const std : : string & file_name , const sensor_msgs : : PointCloud2 & cloud ,
const Eigen : : Vector4f & origin = Eigen : : Vector4f : : Zero ( ) ,
const Eigen : : Quaternionf & orientation = Eigen : : Quaternionf : : Identity ( ) ,
const bool binary_mode = false )
{
pcl : : PCLPointCloud2 pcl_cloud ;
pcl_conversions : : toPCL ( cloud , pcl_cloud ) ;
return pcl : : io : : savePCDFile ( file_name , pcl_cloud , origin , orientation , binary_mode ) ;
}
2013-07-08 16:34:15 -07:00
2013-07-09 18:55:42 -07:00
inline int
destructiveSavePCDFile ( const std : : string & file_name , sensor_msgs : : PointCloud2 & cloud ,
const Eigen : : Vector4f & origin = Eigen : : Vector4f : : Zero ( ) ,
const Eigen : : Quaternionf & orientation = Eigen : : Quaternionf : : Identity ( ) ,
const bool binary_mode = false )
{
pcl : : PCLPointCloud2 pcl_cloud ;
pcl_conversions : : moveToPCL ( cloud , pcl_cloud ) ;
return pcl : : io : : savePCDFile ( file_name , pcl_cloud , origin , orientation , binary_mode ) ;
}
2013-07-08 16:34:15 -07:00
2013-07-09 18:55:42 -07:00
/** Overload pcl::io::loadPCDFile **/
2013-07-09 21:49:26 -07:00
2013-07-09 18:55:42 -07:00
inline int loadPCDFile ( const std : : string & file_name , sensor_msgs : : PointCloud2 & cloud )
{
pcl : : PCLPointCloud2 pcl_cloud ;
int ret = pcl : : io : : loadPCDFile ( file_name , pcl_cloud ) ;
pcl_conversions : : moveFromPCL ( pcl_cloud , cloud ) ;
return ret ;
}
2013-07-08 16:34:15 -07:00
2013-07-09 18:55:42 -07:00
} // namespace io
2013-07-08 16:34:15 -07:00
2013-07-09 18:55:42 -07:00
/** Overload asdf **/
inline
bool concatenatePointCloud ( const sensor_msgs : : PointCloud2 & cloud1 ,
const sensor_msgs : : PointCloud2 & cloud2 ,
sensor_msgs : : PointCloud2 & cloud_out )
{
//if one input cloud has no points, but the other input does, just return the cloud with points
if ( cloud1 . width * cloud1 . height = = 0 & & cloud2 . width * cloud2 . height > 0 )
{
cloud_out = cloud2 ;
return ( true ) ;
}
else if ( cloud1 . width * cloud1 . height > 0 & & cloud2 . width * cloud2 . height = = 0 )
{
cloud_out = cloud1 ;
return ( true ) ;
}
bool strip = false ;
for ( size_t i = 0 ; i < cloud1 . fields . size ( ) ; + + i )
if ( cloud1 . fields [ i ] . name = = " _ " )
strip = true ;
for ( size_t i = 0 ; i < cloud2 . fields . size ( ) ; + + i )
if ( cloud2 . fields [ i ] . name = = " _ " )
strip = true ;
if ( ! strip & & cloud1 . fields . size ( ) ! = cloud2 . fields . size ( ) )
{
PCL_ERROR ( " [pcl::concatenatePointCloud] Number of fields in cloud1 (%u) != Number of fields in cloud2 (%u) \n " , cloud1 . fields . size ( ) , cloud2 . fields . size ( ) ) ;
return ( false ) ;
}
// Copy cloud1 into cloud_out
cloud_out = cloud1 ;
size_t nrpts = cloud_out . data . size ( ) ;
// Height = 1 => no more organized
cloud_out . width = cloud1 . width * cloud1 . height + cloud2 . width * cloud2 . height ;
cloud_out . height = 1 ;
if ( ! cloud1 . is_dense | | ! cloud2 . is_dense )
cloud_out . is_dense = false ;
else
cloud_out . is_dense = true ;
// We need to strip the extra padding fields
if ( strip )
{
// Get the field sizes for the second cloud
std : : vector < sensor_msgs : : PointField > fields2 ;
std : : vector < int > fields2_sizes ;
for ( size_t j = 0 ; j < cloud2 . fields . size ( ) ; + + j )
{
if ( cloud2 . fields [ j ] . name = = " _ " )
continue ;
fields2_sizes . push_back ( cloud2 . fields [ j ] . count *
pcl : : getFieldSize ( cloud2 . fields [ j ] . datatype ) ) ;
fields2 . push_back ( cloud2 . fields [ j ] ) ;
}
cloud_out . data . resize ( nrpts + ( cloud2 . width * cloud2 . height ) * cloud_out . point_step ) ;
// Copy the second cloud
for ( size_t cp = 0 ; cp < cloud2 . width * cloud2 . height ; + + cp )
{
int i = 0 ;
for ( size_t j = 0 ; j < fields2 . size ( ) ; + + j )
{
if ( cloud1 . fields [ i ] . name = = " _ " )
{
+ + i ;
continue ;
}
// We're fine with the special RGB vs RGBA use case
if ( ( cloud1 . fields [ i ] . name = = " rgb " & & fields2 [ j ] . name = = " rgba " ) | |
( cloud1 . fields [ i ] . name = = " rgba " & & fields2 [ j ] . name = = " rgb " ) | |
( cloud1 . fields [ i ] . name = = fields2 [ j ] . name ) )
{
memcpy ( reinterpret_cast < char * > ( & cloud_out . data [ nrpts + cp * cloud1 . point_step + cloud1 . fields [ i ] . offset ] ) ,
reinterpret_cast < const char * > ( & cloud2 . data [ cp * cloud2 . point_step + cloud2 . fields [ j ] . offset ] ) ,
fields2_sizes [ j ] ) ;
+ + i ; // increment the field size i
}
}
}
}
else
{
for ( size_t i = 0 ; i < cloud1 . fields . size ( ) ; + + i )
{
// We're fine with the special RGB vs RGBA use case
if ( ( cloud1 . fields [ i ] . name = = " rgb " & & cloud2 . fields [ i ] . name = = " rgba " ) | |
( cloud1 . fields [ i ] . name = = " rgba " & & cloud2 . fields [ i ] . name = = " rgb " ) )
continue ;
// Otherwise we need to make sure the names are the same
if ( cloud1 . fields [ i ] . name ! = cloud2 . fields [ i ] . name )
{
PCL_ERROR ( " [pcl::concatenatePointCloud] Name of field %d in cloud1, %s, does not match name in cloud2, %s \n " , i , cloud1 . fields [ i ] . name . c_str ( ) , cloud2 . fields [ i ] . name . c_str ( ) ) ;
return ( false ) ;
}
}
cloud_out . data . resize ( nrpts + cloud2 . data . size ( ) ) ;
memcpy ( & cloud_out . data [ nrpts ] , & cloud2 . data [ 0 ] , cloud2 . data . size ( ) ) ;
}
return ( true ) ;
}
} // namespace pcl
2013-07-08 16:34:15 -07:00
namespace ros
{
template < >
struct DefaultMessageCreator < pcl : : PCLPointCloud2 >
{
boost : : shared_ptr < pcl : : PCLPointCloud2 > operator ( ) ( )
{
boost : : shared_ptr < pcl : : PCLPointCloud2 > msg ( new pcl : : PCLPointCloud2 ( ) ) ;
return msg ;
}
} ;
namespace message_traits
{
template < >
struct MD5Sum < pcl : : PCLPointCloud2 >
{
static const char * value ( ) { return MD5Sum < sensor_msgs : : PointCloud2 > : : value ( ) ; }
static const char * value ( const pcl : : PCLPointCloud2 & ) { return value ( ) ; }
static const uint64_t static_value1 = MD5Sum < sensor_msgs : : PointCloud2 > : : static_value1 ;
static const uint64_t static_value2 = MD5Sum < sensor_msgs : : PointCloud2 > : : static_value2 ;
// If the definition of sensor_msgs/PointCloud2 changes, we'll get a compile error here.
ROS_STATIC_ASSERT ( static_value1 = = 0x1158d486dd51d683ULL ) ;
ROS_STATIC_ASSERT ( static_value2 = = 0xce2f1be655c3c181ULL ) ;
} ;
template < >
struct DataType < pcl : : PCLPointCloud2 >
{
static const char * value ( ) { return DataType < sensor_msgs : : PointCloud2 > : : value ( ) ; }
static const char * value ( const pcl : : PCLPointCloud2 & ) { return value ( ) ; }
} ;
template < >
struct Definition < pcl : : PCLPointCloud2 >
{
static const char * value ( ) { return Definition < sensor_msgs : : PointCloud2 > : : value ( ) ; }
static const char * value ( const pcl : : PCLPointCloud2 & ) { return value ( ) ; }
} ;
template < > struct HasHeader < pcl : : PCLPointCloud2 > : TrueType { } ;
} // namespace ros::message_traits
namespace serialization
{
2013-07-09 18:55:42 -07:00
/*
* Provide a custom serialization for pcl : : PCLPointCloud2
*/
2013-07-08 16:34:15 -07:00
template < >
struct Serializer < pcl : : PCLPointCloud2 >
{
template < typename Stream >
inline static void write ( Stream & stream , const pcl : : PCLPointCloud2 & m )
{
std_msgs : : Header header ;
pcl_conversions : : fromPCL ( m . header , header ) ;
stream . next ( header ) ;
stream . next ( m . height ) ;
stream . next ( m . width ) ;
std : : vector < sensor_msgs : : PointField > pfs ;
pcl_conversions : : fromPCL ( m . fields , pfs ) ;
stream . next ( pfs ) ;
stream . next ( m . is_bigendian ) ;
stream . next ( m . point_step ) ;
stream . next ( m . row_step ) ;
stream . next ( m . data ) ;
stream . next ( m . is_dense ) ;
}
template < typename Stream >
inline static void read ( Stream & stream , pcl : : PCLPointCloud2 & m )
{
std_msgs : : Header header ;
stream . next ( header ) ;
pcl_conversions : : toPCL ( header , m . header ) ;
stream . next ( m . height ) ;
stream . next ( m . width ) ;
std : : vector < sensor_msgs : : PointField > pfs ;
stream . next ( pfs ) ;
pcl_conversions : : toPCL ( pfs , m . fields ) ;
stream . next ( m . is_bigendian ) ;
stream . next ( m . point_step ) ;
stream . next ( m . row_step ) ;
stream . next ( m . data ) ;
stream . next ( m . is_dense ) ;
}
inline static uint32_t serializedLength ( const pcl : : PCLPointCloud2 & m )
{
uint32_t length = 0 ;
std_msgs : : Header header ;
pcl_conversions : : fromPCL ( m . header , header ) ;
length + = serializationLength ( header ) ;
length + = 4 ; // height
length + = 4 ; // width
std : : vector < sensor_msgs : : PointField > pfs ;
pcl_conversions : : fromPCL ( m . fields , pfs ) ;
length + = serializationLength ( pfs ) ; // fields
length + = 1 ; // is_bigendian
length + = 4 ; // point_step
length + = 4 ; // row_step
length + = 4 ; // data's size
length + = m . data . size ( ) * sizeof ( pcl : : uint8_t ) ;
length + = 1 ; // is_dense
return length ;
}
} ;
2013-07-09 18:55:42 -07:00
/*
* Provide a custom serialization for pcl : : PCLPointField
*/
template < >
struct Serializer < pcl : : PCLPointField >
{
template < typename Stream >
inline static void write ( Stream & stream , const pcl : : PCLPointField & m )
{
stream . next ( m . name ) ;
stream . next ( m . offset ) ;
stream . next ( m . datatype ) ;
stream . next ( m . count ) ;
}
template < typename Stream >
inline static void read ( Stream & stream , pcl : : PCLPointField & m )
{
stream . next ( m . name ) ;
stream . next ( m . offset ) ;
stream . next ( m . datatype ) ;
stream . next ( m . count ) ;
}
inline static uint32_t serializedLength ( const pcl : : PCLPointField & m )
{
uint32_t length = 0 ;
length + = serializationLength ( m . name ) ;
length + = serializationLength ( m . offset ) ;
length + = serializationLength ( m . datatype ) ;
length + = serializationLength ( m . count ) ;
return length ;
}
} ;
/*
* Provide a custom serialization for pcl : : PCLHeader
*/
2013-07-08 16:34:15 -07:00
template < >
struct Serializer < pcl : : PCLHeader >
{
template < typename Stream >
inline static void write ( Stream & stream , const pcl : : PCLHeader & m )
{
std_msgs : : Header header ;
pcl_conversions : : fromPCL ( m , header ) ;
stream . next ( header ) ;
}
template < typename Stream >
inline static void read ( Stream & stream , pcl : : PCLHeader & m )
{
std_msgs : : Header header ;
stream . next ( header ) ;
pcl_conversions : : toPCL ( header , m ) ;
}
inline static uint32_t serializedLength ( const pcl : : PCLHeader & m )
{
uint32_t length = 0 ;
std_msgs : : Header header ;
pcl_conversions : : fromPCL ( m , header ) ;
length + = serializationLength ( header ) ;
return length ;
}
} ;
} // namespace ros::serialization
} // namespace ros
2013-07-08 18:50:55 -07:00
# endif /* PCL_CONVERSIONS_H__ */