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 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 #include <dynamic_reconfigure/server.h> 00026 #include <velodyne_pointcloud/VelodyneConfigConfig.h> 00027 00028 namespace velodyne_pointcloud 00029 { 00030 class Convert 00031 { 00032 public: 00033 00034 Convert(ros::NodeHandle node, ros::NodeHandle private_nh); 00035 ~Convert() {} 00036 00037 private: 00038 00039 void callback(velodyne_pointcloud::VelodyneConfigConfig &config, 00040 uint32_t level); 00041 void processScan(const velodyne_msgs::VelodyneScan::ConstPtr &scanMsg); 00042 00044 boost::shared_ptr<dynamic_reconfigure::Server<velodyne_pointcloud:: 00045 VelodyneConfigConfig> > srv_; 00046 00047 boost::shared_ptr<velodyne_rawdata::RawData> data_; 00048 ros::Subscriber velodyne_scan_; 00049 ros::Publisher output_; 00050 00052 typedef struct { 00053 int npackets; 00054 } Config; 00055 Config config_; 00056 }; 00057 00058 } // namespace velodyne_pointcloud 00059 00060 #endif // _VELODYNE_POINTCLOUD_CONVERT_H_