point_cloud.h
Go to the documentation of this file.
00001 #ifndef __POINTMATCHER_ROS_POINT_CLOUD_H
00002 #define __POINTMATCHER_ROS_POINT_CLOUD_H
00003 
00004 #include "pointmatcher/PointMatcher.h"
00005 #include "sensor_msgs/PointCloud2.h"
00006 #include "sensor_msgs/LaserScan.h"
00007 
00008 namespace ros
00009 {
00010         struct Time;
00011 };
00012 namespace tf
00013 {
00014         struct TransformListener;
00015 };
00016 
00017 namespace PointMatcher_ros
00018 {
00019         template<typename T>
00020         typename PointMatcher<T>::DataPoints rosMsgToPointMatcherCloud(const sensor_msgs::PointCloud2& rosMsg);
00021         
00022         template<typename T>
00023         typename PointMatcher<T>::DataPoints rosMsgToPointMatcherCloud(const sensor_msgs::LaserScan& rosMsg, const tf::TransformListener* listener = 0, const std::string& fixed_frame = "/world", const bool force3D = false, const bool addTimestamps=false);
00024         
00025         template<typename T>
00026         sensor_msgs::PointCloud2 pointMatcherCloudToRosMsg(const typename PointMatcher<T>::DataPoints& pmCloud, const std::string& frame_id, const ros::Time& stamp);
00027 }; // PointMatcher_ros
00028 
00029 #endif //__POINTMATCHER_ROS_POINT_CLOUD_H


libpointmatcher_ros
Author(s): Stéphane Magnenat, Francois Pomerleau
autogenerated on Tue Mar 3 2015 15:28:40