$search
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: convert.h 2225 2012-03-27 15:37:00Z jack.oquin $ 00009 */ 00010 00017 #ifndef _VELODYNE_POINTCLOUD_CONVERT_H_ 00018 #define _VELODYNE_POINTCLOUD_CONVERT_H_ 1 00019 00020 #include <ros/ros.h> 00021 00022 #include <sensor_msgs/PointCloud2.h> 00023 #include <velodyne_pointcloud/rawdata.h> 00024 00025 namespace velodyne_pointcloud 00026 { 00027 class Convert 00028 { 00029 public: 00030 00031 Convert(ros::NodeHandle node, ros::NodeHandle private_nh); 00032 ~Convert() {} 00033 00034 private: 00035 00036 void processScan(const velodyne_msgs::VelodyneScan::ConstPtr &scanMsg); 00037 00038 boost::shared_ptr<velodyne_rawdata::RawData> data_; 00039 ros::Subscriber velodyne_scan_; 00040 ros::Publisher output_; 00041 00043 typedef struct { 00044 int npackets; 00045 } Config; 00046 Config config_; 00047 }; 00048 00049 } // namespace velodyne_pointcloud 00050 00051 #endif // _VELODYNE_POINTCLOUD_CONVERT_H_