00001 /* -*- mode: C++ -*- */ 00002 /* 00003 * Copyright (C) 2012 Austin Robot Technology, Jack O'Quin 00004 * 00005 * License: Modified BSD Software License Agreement 00006 * 00007 * $Id$ 00008 */ 00009 00015 #ifndef _VELODYNE_DRIVER_H_ 00016 #define _VELODYNE_DRIVER_H_ 1 00017 00018 #include <string> 00019 #include <ros/ros.h> 00020 #include <diagnostic_updater/diagnostic_updater.h> 00021 #include <diagnostic_updater/publisher.h> 00022 00023 #include <velodyne_driver/input.h> 00024 00025 namespace velodyne_driver 00026 { 00027 00028 class VelodyneDriver 00029 { 00030 public: 00031 00032 VelodyneDriver(ros::NodeHandle node, 00033 ros::NodeHandle private_nh); 00034 ~VelodyneDriver() {} 00035 00036 bool poll(void); 00037 00038 private: 00039 00040 // configuration parameters 00041 struct 00042 { 00043 std::string frame_id; 00044 std::string model; 00045 int npackets; 00046 double rpm; 00047 } config_; 00048 00049 boost::shared_ptr<Input> input_; 00050 ros::Publisher output_; 00051 00053 diagnostic_updater::Updater diagnostics_; 00054 double diag_min_freq_; 00055 double diag_max_freq_; 00056 boost::shared_ptr<diagnostic_updater::TopicDiagnostic> diag_topic_; 00057 }; 00058 00059 } // namespace velodyne_driver 00060 00061 #endif // _VELODYNE_DRIVER_H_