diff --git a/pcl_ros/include/pcl_ros/features/feature.h b/pcl_ros/include/pcl_ros/features/feature.h index 7ef9d644..3d5f9604 100644 --- a/pcl_ros/include/pcl_ros/features/feature.h +++ b/pcl_ros/include/pcl_ros/features/feature.h @@ -49,6 +49,9 @@ #include #include "pcl_ros/FeatureConfig.h" +// PCL conversions +#include + namespace pcl_ros { namespace sync_policies = message_filters::sync_policies; @@ -147,7 +150,7 @@ namespace pcl_ros input_callback (const PointCloudInConstPtr &input) { PointIndices indices; - indices.header.stamp = input->header.stamp; + indices.header.stamp = pcl_conversions::fromPCL(input->header).stamp; PointCloudIn cloud; cloud.header.stamp = input->header.stamp; nf_pc_.add (cloud.makeShared ()); diff --git a/pcl_ros/include/pcl_ros/impl/transforms.hpp b/pcl_ros/include/pcl_ros/impl/transforms.hpp index 26fcbc3b..52b49e25 100644 --- a/pcl_ros/include/pcl_ros/impl/transforms.hpp +++ b/pcl_ros/include/pcl_ros/impl/transforms.hpp @@ -37,8 +37,12 @@ #ifndef pcl_ros_IMPL_TRANSFORMS_H_ #define pcl_ros_IMPL_TRANSFORMS_H_ +#include #include "pcl_ros/transforms.h" +using pcl_conversions::fromPCL; +using pcl_conversions::toPCL; + namespace pcl_ros { ////////////////////////////////////////////////////////////////////////////////////////////// @@ -99,7 +103,7 @@ transformPointCloudWithNormals (const std::string &target_frame, tf::StampedTransform transform; try { - tf_listener.lookupTransform (target_frame, cloud_in.header.frame_id, cloud_in.header.stamp, transform); + tf_listener.lookupTransform (target_frame, cloud_in.header.frame_id, fromPCL(cloud_in.header).stamp, transform); } catch (tf::LookupException &e) { @@ -133,7 +137,7 @@ transformPointCloud (const std::string &target_frame, tf::StampedTransform transform; try { - tf_listener.lookupTransform (target_frame, cloud_in.header.frame_id, cloud_in.header.stamp, transform); + tf_listener.lookupTransform (target_frame, cloud_in.header.frame_id, fromPCL(cloud_in.header).stamp, transform); } catch (tf::LookupException &e) { @@ -162,7 +166,7 @@ transformPointCloud (const std::string &target_frame, tf::StampedTransform transform; try { - tf_listener.lookupTransform (target_frame, target_time, cloud_in.header.frame_id, cloud_in.header.stamp, fixed_frame, transform); + tf_listener.lookupTransform (target_frame, target_time, cloud_in.header.frame_id, fromPCL(cloud_in.header).stamp, fixed_frame, transform); } catch (tf::LookupException &e) { @@ -177,7 +181,9 @@ transformPointCloud (const std::string &target_frame, transformPointCloud (cloud_in, cloud_out, transform); cloud_out.header.frame_id = target_frame; - cloud_out.header.stamp = target_time; + std_msgs::Header header; + header.stamp = target_time; + cloud_out.header = toPCL(header); return (true); } @@ -193,7 +199,7 @@ transformPointCloudWithNormals (const std::string &target_frame, tf::StampedTransform transform; try { - tf_listener.lookupTransform (target_frame, target_time, cloud_in.header.frame_id, cloud_in.header.stamp, fixed_frame, transform); + tf_listener.lookupTransform (target_frame, target_time, cloud_in.header.frame_id, fromPCL(cloud_in.header).stamp, fixed_frame, transform); } catch (tf::LookupException &e) { @@ -208,7 +214,9 @@ transformPointCloudWithNormals (const std::string &target_frame, transformPointCloudWithNormals (cloud_in, cloud_out, transform); cloud_out.header.frame_id = target_frame; - cloud_out.header.stamp = target_time; + std_msgs::Header header; + header.stamp = target_time; + cloud_out.header = toPCL(header); return (true); } diff --git a/pcl_ros/include/pcl_ros/pcl_nodelet.h b/pcl_ros/include/pcl_ros/pcl_nodelet.h index 9fef5ba7..dbb8b460 100644 --- a/pcl_ros/include/pcl_ros/pcl_nodelet.h +++ b/pcl_ros/include/pcl_ros/pcl_nodelet.h @@ -46,9 +46,10 @@ #include // PCL includes -#include +#include #include #include +#include #include "pcl_ros/point_cloud.h" // ROS Nodelet includes #include @@ -60,6 +61,8 @@ // Include TF #include +using pcl_conversions::fromPCL; + namespace pcl_ros { //////////////////////////////////////////////////////////////////////////////////////////// @@ -75,7 +78,7 @@ namespace pcl_ros typedef PointCloud::Ptr PointCloudPtr; typedef PointCloud::ConstPtr PointCloudConstPtr; - typedef pcl::PointIndices PointIndices; + typedef pcl_msgs::PointIndices PointIndices; typedef PointIndices::Ptr PointIndicesPtr; typedef PointIndices::ConstPtr PointIndicesConstPtr; @@ -157,7 +160,7 @@ namespace pcl_ros { if (cloud->width * cloud->height != cloud->points.size ()) { - NODELET_WARN ("[%s] Invalid PointCloud (points = %zu, width = %d, height = %d) with stamp %f, and frame %s on topic %s received!", getName ().c_str (), cloud->points.size (), cloud->width, cloud->height, cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName (topic_name).c_str ()); + NODELET_WARN ("[%s] Invalid PointCloud (points = %zu, width = %d, height = %d) with stamp %f, and frame %s on topic %s received!", getName ().c_str (), cloud->points.size (), cloud->width, cloud->height, fromPCL(cloud->header).stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName (topic_name).c_str ()); return (false); } diff --git a/pcl_ros/include/pcl_ros/publisher.h b/pcl_ros/include/pcl_ros/publisher.h index 1bba8e2c..b019ba9b 100644 --- a/pcl_ros/include/pcl_ros/publisher.h +++ b/pcl_ros/include/pcl_ros/publisher.h @@ -46,7 +46,8 @@ #define PCL_ROS_PUBLISHER_H_ #include -#include +#include +#include namespace pcl_ros { diff --git a/pcl_ros/src/pcl_ros/features/feature.cpp b/pcl_ros/src/pcl_ros/features/feature.cpp index 434707ee..0625279b 100644 --- a/pcl_ros/src/pcl_ros/features/feature.cpp +++ b/pcl_ros/src/pcl_ros/features/feature.cpp @@ -204,25 +204,25 @@ pcl_ros::Feature::input_surface_indices_callback (const PointCloudInConstPtr &cl " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" " - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.", - cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (), - cloud_surface->width * cloud_surface->height, pcl::getFieldsList (*cloud_surface).c_str (), cloud_surface->header.stamp.toSec (), cloud_surface->header.frame_id.c_str (), pnh_->resolveName ("surface").c_str (), + cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), fromPCL(cloud->header).stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (), + cloud_surface->width * cloud_surface->height, pcl::getFieldsList (*cloud_surface).c_str (), fromPCL(cloud_surface->header).stamp.toSec (), cloud_surface->header.frame_id.c_str (), pnh_->resolveName ("surface").c_str (), indices->indices.size (), indices->header.stamp.toSec (), indices->header.frame_id.c_str (), pnh_->resolveName ("indices").c_str ()); else NODELET_DEBUG ("[input_surface_indices_callback]\n" " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.", - cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (), - cloud_surface->width * cloud_surface->height, pcl::getFieldsList (*cloud_surface).c_str (), cloud_surface->header.stamp.toSec (), cloud_surface->header.frame_id.c_str (), pnh_->resolveName ("surface").c_str ()); + cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), fromPCL(cloud->header).stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (), + cloud_surface->width * cloud_surface->height, pcl::getFieldsList (*cloud_surface).c_str (), fromPCL(cloud_surface->header).stamp.toSec (), cloud_surface->header.frame_id.c_str (), pnh_->resolveName ("surface").c_str ()); else if (indices) NODELET_DEBUG ("[input_surface_indices_callback]\n" " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" " - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.", - cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (), + cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), fromPCL(cloud->header).stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (), indices->indices.size (), indices->header.stamp.toSec (), indices->header.frame_id.c_str (), pnh_->resolveName ("indices").c_str ()); else - NODELET_DEBUG ("[input_surface_indices_callback] PointCloud with %d data points, stamp %f, and frame %s on topic %s received.", cloud->width * cloud->height, cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str ()); + NODELET_DEBUG ("[input_surface_indices_callback] PointCloud with %d data points, stamp %f, and frame %s on topic %s received.", cloud->width * cloud->height, fromPCL(cloud->header).stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str ()); /// @@ -394,9 +394,9 @@ pcl_ros::FeatureFromNormals::input_normals_surface_indices_callback ( " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" " - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.", getName ().c_str (), - cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (), - cloud_surface->width * cloud_surface->height, pcl::getFieldsList (*cloud_surface).c_str (), cloud_surface->header.stamp.toSec (), cloud_surface->header.frame_id.c_str (), pnh_->resolveName ("surface").c_str (), - cloud_normals->width * cloud_normals->height, pcl::getFieldsList (*cloud_normals).c_str (), cloud_normals->header.stamp.toSec (), cloud_normals->header.frame_id.c_str (), pnh_->resolveName ("normals").c_str (), + cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), fromPCL(cloud->header).stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (), + cloud_surface->width * cloud_surface->height, pcl::getFieldsList (*cloud_surface).c_str (), fromPCL(cloud_surface->header).stamp.toSec (), cloud_surface->header.frame_id.c_str (), pnh_->resolveName ("surface").c_str (), + cloud_normals->width * cloud_normals->height, pcl::getFieldsList (*cloud_normals).c_str (), fromPCL(cloud_normals->header).stamp.toSec (), cloud_normals->header.frame_id.c_str (), pnh_->resolveName ("normals").c_str (), indices->indices.size (), indices->header.stamp.toSec (), indices->header.frame_id.c_str (), pnh_->resolveName ("indices").c_str ()); else NODELET_DEBUG ("[%s::input_normals_surface_indices_callback]\n" @@ -404,9 +404,9 @@ pcl_ros::FeatureFromNormals::input_normals_surface_indices_callback ( " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.", getName ().c_str (), - cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (), - cloud_surface->width * cloud_surface->height, pcl::getFieldsList (*cloud_surface).c_str (), cloud_surface->header.stamp.toSec (), cloud_surface->header.frame_id.c_str (), pnh_->resolveName ("surface").c_str (), - cloud_normals->width * cloud_normals->height, pcl::getFieldsList (*cloud_normals).c_str (), cloud_normals->header.stamp.toSec (), cloud_normals->header.frame_id.c_str (), pnh_->resolveName ("normals").c_str ()); + cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), fromPCL(cloud->header).stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (), + cloud_surface->width * cloud_surface->height, pcl::getFieldsList (*cloud_surface).c_str (), fromPCL(cloud_surface->header).stamp.toSec (), cloud_surface->header.frame_id.c_str (), pnh_->resolveName ("surface").c_str (), + cloud_normals->width * cloud_normals->height, pcl::getFieldsList (*cloud_normals).c_str (), fromPCL(cloud_normals->header).stamp.toSec (), cloud_normals->header.frame_id.c_str (), pnh_->resolveName ("normals").c_str ()); else if (indices) NODELET_DEBUG ("[%s::input_normals_surface_indices_callback]\n" @@ -414,16 +414,16 @@ pcl_ros::FeatureFromNormals::input_normals_surface_indices_callback ( " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" " - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.", getName ().c_str (), - cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (), - cloud_normals->width * cloud_normals->height, pcl::getFieldsList (*cloud_normals).c_str (), cloud_normals->header.stamp.toSec (), cloud_normals->header.frame_id.c_str (), pnh_->resolveName ("normals").c_str (), + cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), fromPCL(cloud->header).stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (), + cloud_normals->width * cloud_normals->height, pcl::getFieldsList (*cloud_normals).c_str (), fromPCL(cloud_normals->header).stamp.toSec (), cloud_normals->header.frame_id.c_str (), pnh_->resolveName ("normals").c_str (), indices->indices.size (), indices->header.stamp.toSec (), indices->header.frame_id.c_str (), pnh_->resolveName ("indices").c_str ()); else NODELET_DEBUG ("[%s::input_normals_surface_indices_callback]\n" " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.", getName ().c_str (), - cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (), - cloud_normals->width * cloud_normals->height, pcl::getFieldsList (*cloud_normals).c_str (), cloud_normals->header.stamp.toSec (), cloud_normals->header.frame_id.c_str (), pnh_->resolveName ("normals").c_str ()); + cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), fromPCL(cloud->header).stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (), + cloud_normals->width * cloud_normals->height, pcl::getFieldsList (*cloud_normals).c_str (), fromPCL(cloud_normals->header).stamp.toSec (), cloud_normals->header.frame_id.c_str (), pnh_->resolveName ("normals").c_str ()); /// if ((int)(cloud->width * cloud->height) < k_) diff --git a/pcl_ros/src/transforms.cpp b/pcl_ros/src/transforms.cpp index d35e2366..75fc6c4e 100644 --- a/pcl_ros/src/transforms.cpp +++ b/pcl_ros/src/transforms.cpp @@ -37,6 +37,7 @@ #include #include #include +#include #include "pcl_ros/transforms.h" #include "pcl_ros/impl/transforms.hpp" diff --git a/pcl_ros/tools/bag_to_pcd.cpp b/pcl_ros/tools/bag_to_pcd.cpp index f66d74b5..b9114cf9 100644 --- a/pcl_ros/tools/bag_to_pcd.cpp +++ b/pcl_ros/tools/bag_to_pcd.cpp @@ -50,6 +50,7 @@ Cloud Data) format. #include #include #include +#include #include "pcl_ros/transforms.h" #include #include diff --git a/pcl_ros/tools/convert_pcd_to_image.cpp b/pcl_ros/tools/convert_pcd_to_image.cpp index 2325f513..ff8e28af 100644 --- a/pcl_ros/tools/convert_pcd_to_image.cpp +++ b/pcl_ros/tools/convert_pcd_to_image.cpp @@ -48,9 +48,11 @@ #include #include +#include #include #include #include +#include /* ---[ */ int @@ -74,7 +76,7 @@ main (int argc, char **argv) { pcl::toROSMsg (cloud, image); //convert the cloud } - catch (std::runtime_error e) + catch (std::runtime_error &e) { ROS_ERROR_STREAM("Error in converting cloud to image message: " << e.what()); diff --git a/pcl_ros/tools/convert_pointcloud_to_image.cpp b/pcl_ros/tools/convert_pointcloud_to_image.cpp index ebadd99d..0fdd5e87 100644 --- a/pcl_ros/tools/convert_pointcloud_to_image.cpp +++ b/pcl_ros/tools/convert_pointcloud_to_image.cpp @@ -42,8 +42,11 @@ #include //Image message #include +#include //pcl::toROSMsg #include +//conversions from PCL custom types +#include //stl stuff #include @@ -59,7 +62,7 @@ public: { pcl::toROSMsg (*cloud, image_); //convert the cloud } - catch (std::runtime_error e) + catch (std::runtime_error &e) { ROS_ERROR_STREAM("Error in converting cloud to image message: " << e.what()); diff --git a/pcl_ros/tools/pcd_to_pointcloud.cpp b/pcl_ros/tools/pcd_to_pointcloud.cpp index bbb3e769..655b4341 100644 --- a/pcl_ros/tools/pcd_to_pointcloud.cpp +++ b/pcl_ros/tools/pcd_to_pointcloud.cpp @@ -48,6 +48,7 @@ #include #include #include +#include #include "pcl_ros/publisher.h" diff --git a/perception_pcl/package.xml b/perception_pcl/package.xml index 5aeaac6b..9ac4e385 100644 --- a/perception_pcl/package.xml +++ b/perception_pcl/package.xml @@ -15,6 +15,8 @@ catkin + pcl_conversions + pcl_msgs pcl_ros