transform.h
Go to the documentation of this file.
00001 /* -*- mode: C++ -*- */
00002 /*
00003  *  Copyright (C) 2009, 2010 Austin Robot Technology, Jack O'Quin
00004  *  Copyright (C) 2011 Jesse Vera
00005  *  Copyright (C) 2012 Austin Robot Technology, Jack O'Quin
00006  *  License: Modified BSD Software License Agreement
00007  *
00008  *  $Id$
00009  */
00010 
00018 #ifndef _VELODYNE_POINTCLOUD_TRANSFORM_H_
00019 #define _VELODYNE_POINTCLOUD_TRANSFORM_H_ 1
00020 
00021 #include <ros/ros.h>
00022 #include "tf/message_filter.h"
00023 #include "message_filters/subscriber.h"
00024 #include <sensor_msgs/PointCloud2.h>
00025 
00026 #include <velodyne_pointcloud/rawdata.h>
00027 #include <velodyne_pointcloud/point_types.h>
00028 
00029 // include template implementations to transform a custom point cloud
00030 #include <pcl_ros/impl/transforms.hpp>
00031 
00033 typedef velodyne_rawdata::VPoint VPoint;
00034 typedef velodyne_rawdata::VPointCloud VPointCloud;
00035 
00036 // instantiate template for transforming a VPointCloud
00037 template bool
00038   pcl_ros::transformPointCloud<VPoint>(const std::string &,
00039                                        const VPointCloud &,
00040                                        VPointCloud &,
00041                                        const tf::TransformListener &);
00042 
00043 namespace velodyne_pointcloud
00044 {
00045   class Transform
00046   {
00047   public:
00048 
00049     Transform(ros::NodeHandle node, ros::NodeHandle private_nh);
00050     ~Transform() {}
00051 
00052   private:
00053 
00054     void processScan(const velodyne_msgs::VelodyneScan::ConstPtr &scanMsg);
00055 
00056     boost::shared_ptr<velodyne_rawdata::RawData> data_;
00057     message_filters::Subscriber<velodyne_msgs::VelodyneScan> velodyne_scan_;
00058     tf::MessageFilter<velodyne_msgs::VelodyneScan> *tf_filter_;
00059     ros::Publisher output_;
00060     tf::TransformListener listener_;
00061 
00063     typedef struct {
00064       std::string frame_id;          
00065     } Config;
00066     Config config_;
00067 
00068     // Point cloud buffers for collecting points within a packet.  The
00069     // inPc_ and tfPc_ are class members only to avoid reallocation on
00070     // every message.
00071     VPointCloud inPc_;              
00072     VPointCloud tfPc_;              
00073   };
00074 
00075 } // namespace velodyne_pointcloud
00076 
00077 #endif // _VELODYNE_POINTCLOUD_TRANSFORM_H_


velodyne_pointcloud
Author(s): Jack O'Quin, Piyush Khandelwal, Jesse Vera
autogenerated on Mon Oct 6 2014 08:36:38