00001 // Copyright (C) 2012 Austin Robot Technology, Jack O'Quin 00002 // All rights reserved. 00003 // 00004 // Software License Agreement (BSD License 2.0) 00005 // 00006 // Redistribution and use in source and binary forms, with or without 00007 // modification, are permitted provided that the following conditions 00008 // are met: 00009 // 00010 // * Redistributions of source code must retain the above copyright 00011 // notice, this list of conditions and the following disclaimer. 00012 // * Redistributions in binary form must reproduce the above 00013 // copyright notice, this list of conditions and the following 00014 // disclaimer in the documentation and/or other materials provided 00015 // with the distribution. 00016 // * Neither the name of {copyright_holder} nor the names of its 00017 // contributors may be used to endorse or promote products derived 00018 // from this software without specific prior written permission. 00019 // 00020 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00021 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00022 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00023 // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00024 // COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00025 // INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00026 // BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00027 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00028 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00029 // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00030 // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00031 // POSSIBILITY OF SUCH DAMAGE. 00032 00033 #ifndef VELODYNE_DRIVER_DRIVER_H 00034 #define VELODYNE_DRIVER_DRIVER_H 00035 00036 #include <string> 00037 #include <ros/ros.h> 00038 #include <diagnostic_updater/diagnostic_updater.h> 00039 #include <diagnostic_updater/publisher.h> 00040 #include <dynamic_reconfigure/server.h> 00041 00042 #include <velodyne_driver/input.h> 00043 #include <velodyne_driver/VelodyneNodeConfig.h> 00044 00045 namespace velodyne_driver 00046 { 00047 00048 class VelodyneDriver 00049 { 00050 public: 00051 VelodyneDriver(ros::NodeHandle node, 00052 ros::NodeHandle private_nh); 00053 ~VelodyneDriver() {} 00054 00055 bool poll(void); 00056 00057 private: 00058 // Callback for dynamic reconfigure 00059 void callback(velodyne_driver::VelodyneNodeConfig &config, 00060 uint32_t level); 00061 // Callback for diagnostics update for lost communication with vlp 00062 void diagTimerCallback(const ros::TimerEvent&event); 00063 00064 // Pointer to dynamic reconfigure service srv_ 00065 boost::shared_ptr<dynamic_reconfigure::Server<velodyne_driver:: 00066 VelodyneNodeConfig> > srv_; 00067 00068 // configuration parameters 00069 struct 00070 { 00071 std::string frame_id; // tf frame ID 00072 std::string model; // device model name 00073 int npackets; // number of packets to collect 00074 double rpm; // device rotation rate (RPMs) 00075 int cut_angle; // cutting angle in 1/100° 00076 double time_offset; // time in seconds added to each velodyne time stamp 00077 bool enabled; // polling is enabled 00078 } 00079 config_; 00080 00081 boost::shared_ptr<Input> input_; 00082 ros::Publisher output_; 00083 int last_azimuth_; 00084 00085 /* diagnostics updater */ 00086 ros::Timer diag_timer_; 00087 diagnostic_updater::Updater diagnostics_; 00088 double diag_min_freq_; 00089 double diag_max_freq_; 00090 boost::shared_ptr<diagnostic_updater::TopicDiagnostic> diag_topic_; 00091 }; 00092 00093 } // namespace velodyne_driver 00094 00095 #endif // VELODYNE_DRIVER_DRIVER_H