urg_node_driver.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2013, Willow Garage, Inc.
00003  * Copyright (c) 2017, Clearpath Robotics, Inc.
00004  * All rights reserved.
00005  *
00006  * Redistribution and use in source and binary forms, with or without
00007  * modification, are permitted provided that the following conditions are met:
00008  *
00009  *     * Redistributions of source code must retain the above copyright
00010  *       notice, this list of conditions and the following disclaimer.
00011  *     * Redistributions in binary form must reproduce the above copyright
00012  *       notice, this list of conditions and the following disclaimer in the
00013  *       documentation and/or other materials provided with the distribution.
00014  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00015  *       contributors may be used to endorse or promote products derived from
00016  *       this software without specific prior written permission.
00017  *
00018  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00019  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00020  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00021  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00022  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00023  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00024  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00025  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00026  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00027  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00028  * POSSIBILITY OF SUCH DAMAGE.
00029  */
00030 
00031 /*
00032  * Author: Mike O'Driscoll
00033  */
00034 
00035 #ifndef URG_NODE_URG_NODE_DRIVER_H
00036 #define URG_NODE_URG_NODE_DRIVER_H
00037 
00038 #include <string>
00039 #include <ros/ros.h>
00040 #include <dynamic_reconfigure/server.h>
00041 #include <laser_proc/LaserTransport.h>
00042 #include <diagnostic_updater/diagnostic_updater.h>
00043 #include <diagnostic_updater/publisher.h>
00044 #include <urg_node/URGConfig.h>
00045 #include <std_srvs/Trigger.h>
00046 
00047 #include "urg_node/urg_c_wrapper.h"
00048 
00049 namespace urg_node
00050 {
00051 class UrgNode
00052 {
00053 public:
00054   UrgNode();
00055   UrgNode(ros::NodeHandle nh, ros::NodeHandle private_nh);
00056   ~UrgNode();
00057 
00061   void run();
00062 
00068   bool updateStatus();
00069 
00070 private:
00071   void initSetup();
00072   bool connect();
00073   bool reconfigure_callback(urg_node::URGConfig& config, int level);
00074   void update_reconfigure_limits();
00075   void calibrate_time_offset();
00076   void updateDiagnostics();
00077   void populateDiagnosticsStatus(diagnostic_updater::DiagnosticStatusWrapper &stat);
00078   void scanThread();
00079 
00080   bool statusCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
00081 
00082   ros::NodeHandle nh_;
00083   ros::NodeHandle pnh_;
00084 
00085   boost::thread diagnostics_thread_;
00086   boost::thread scan_thread_;
00087 
00088   boost::shared_ptr<urg_node::URGCWrapper> urg_;
00089   boost::shared_ptr<dynamic_reconfigure::Server<urg_node::URGConfig> > srv_;  
00090   boost::shared_ptr<diagnostic_updater::Updater> diagnostic_updater_;
00091   boost::shared_ptr<diagnostic_updater::HeaderlessTopicDiagnostic> laser_freq_;
00092   boost::shared_ptr<diagnostic_updater::HeaderlessTopicDiagnostic> echoes_freq_;
00093 
00094   boost::mutex lidar_mutex_;
00095 
00096   /* Non-const device properties.  If you poll the driver for these
00097   * while scanning is running, then the scan will probably fail.
00098   */
00099   std::string device_status_;
00100   std::string vendor_name_;
00101   std::string product_name_;
00102   std::string firmware_version_;
00103   std::string firmware_date_;
00104   std::string protocol_version_;
00105   std::string device_id_;
00106   uint16_t error_code_;
00107   bool lockout_status_;
00108 
00109   int error_count_;
00110   double freq_min_;
00111   bool close_diagnostics_;
00112   bool close_scan_;
00113 
00114   int ip_port_;
00115   std::string ip_address_;
00116   std::string serial_port_;
00117   int serial_baud_;
00118   bool calibrate_time_;
00119   bool synchronize_time_;
00120   bool publish_intensity_;
00121   bool publish_multiecho_;
00122   int error_limit_;
00123   double diagnostics_tolerance_;
00124   double diagnostics_window_time_;
00125   bool detailed_status_;
00126 
00127   volatile bool service_yield_;
00128 
00129   ros::Publisher laser_pub_;
00130   laser_proc::LaserPublisher echoes_pub_;
00131   ros::Publisher status_pub_;
00132 
00133   ros::ServiceServer status_service_;
00134 };
00135 
00136 }  // namespace urg_node
00137 
00138 #endif  // URG_NODE_URG_NODE_DRIVER_H


urg_node
Author(s): Chad Rockey , Mike O'Driscoll
autogenerated on Sat Jun 8 2019 19:16:00