urg_node_driver.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2013, Willow Garage, Inc.
3  * Copyright (c) 2017, Clearpath Robotics, Inc.
4  * All rights reserved.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * * Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * * Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in the
13  * documentation and/or other materials provided with the distribution.
14  * * Neither the name of the Willow Garage, Inc. nor the names of its
15  * contributors may be used to endorse or promote products derived from
16  * this software without specific prior written permission.
17  *
18  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
22  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28  * POSSIBILITY OF SUCH DAMAGE.
29  */
30 
31 /*
32  * Author: Mike O'Driscoll
33  */
34 
35 #ifndef URG_NODE_URG_NODE_DRIVER_H
36 #define URG_NODE_URG_NODE_DRIVER_H
37 
38 #include <string>
39 #include <ros/ros.h>
40 #include <dynamic_reconfigure/server.h>
44 #include <urg_node/URGConfig.h>
45 #include <std_srvs/Trigger.h>
46 #include <bondcpp/bond.h>
47 
48 #include "urg_node/urg_c_wrapper.h"
49 
50 namespace urg_node
51 {
52 class UrgNode
53 {
54 public:
55  UrgNode();
56  UrgNode(ros::NodeHandle nh, ros::NodeHandle private_nh);
57  ~UrgNode();
58 
62  void run();
63 
69  bool updateStatus();
70 
71 private:
72  void initSetup();
73  bool connect();
74  bool reconfigure_callback(urg_node::URGConfig& config, int level);
76  void calibrate_time_offset();
77  void addDiagnostics();
78  void updateDiagnostics();
80  void scanThread();
81 
82  bool statusCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res);
83 
86 
87  boost::thread diagnostics_thread_;
88  boost::thread scan_thread_;
89 
96 
97  boost::mutex lidar_mutex_;
98 
99  /* Non-const device properties. If you poll the driver for these
100  * while scanning is running, then the scan will probably fail.
101  */
102  std::string device_status_;
103  std::string vendor_name_;
104  std::string product_name_;
105  std::string firmware_version_;
106  std::string firmware_date_;
107  std::string protocol_version_;
108  std::string device_id_;
109  uint16_t error_code_;
111 
113  double freq_min_;
116 
117  int ip_port_;
118  std::string ip_address_;
119  std::string serial_port_;
129 
130  volatile bool service_yield_;
131 
135 
137 };
138 
139 } // namespace urg_node
140 
141 #endif // URG_NODE_URG_NODE_DRIVER_H
LaserTransport.h
urg_node::UrgNode::publish_intensity_
bool publish_intensity_
Definition: urg_node_driver.h:123
urg_node::UrgNode::connect
bool connect()
Definition: urg_node_driver.cpp:432
urg_node::UrgNode::nh_
ros::NodeHandle nh_
Definition: urg_node_driver.h:84
urg_node::UrgNode::serial_baud_
int serial_baud_
Definition: urg_node_driver.h:120
urg_node::UrgNode::product_name_
std::string product_name_
Definition: urg_node_driver.h:104
urg_node::UrgNode::~UrgNode
~UrgNode()
Definition: urg_node_driver.cpp:103
urg_node::UrgNode::close_scan_
bool close_scan_
Definition: urg_node_driver.h:115
urg_node::UrgNode::laser_pub_
ros::Publisher laser_pub_
Definition: urg_node_driver.h:132
urg_node::UrgNode::diagnostics_tolerance_
double diagnostics_tolerance_
Definition: urg_node_driver.h:126
urg_node::UrgNode::error_count_
int error_count_
Definition: urg_node_driver.h:112
ros::Publisher
urg_node::UrgNode::diagnostic_updater_
boost::shared_ptr< diagnostic_updater::Updater > diagnostic_updater_
Definition: urg_node_driver.h:93
boost::shared_ptr< bond::Bond >
urg_node::UrgNode::protocol_version_
std::string protocol_version_
Definition: urg_node_driver.h:107
urg_node::UrgNode::bond_
boost::shared_ptr< bond::Bond > bond_
Definition: urg_node_driver.h:90
ros.h
urg_node::UrgNode
Definition: urg_node_driver.h:52
urg_node::UrgNode::UrgNode
UrgNode()
Definition: urg_node_driver.cpp:55
urg_node::UrgNode::diagnostics_thread_
boost::thread diagnostics_thread_
Definition: urg_node_driver.h:87
urg_node::UrgNode::statusCallback
bool statusCallback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
Definition: urg_node_driver.cpp:170
urg_node::UrgNode::calibrate_time_offset
void calibrate_time_offset()
Definition: urg_node_driver.cpp:258
urg_node::UrgNode::lidar_mutex_
boost::mutex lidar_mutex_
Definition: urg_node_driver.h:97
urg_node::UrgNode::publish_multiecho_
bool publish_multiecho_
Definition: urg_node_driver.h:124
urg_node::UrgNode::scan_thread_
boost::thread scan_thread_
Definition: urg_node_driver.h:88
urg_node::UrgNode::scanThread
void scanThread()
Definition: urg_node_driver.cpp:505
urg_node::UrgNode::update_reconfigure_limits
void update_reconfigure_limits()
Definition: urg_node_driver.cpp:237
urg_node::UrgNode::device_id_
std::string device_id_
Definition: urg_node_driver.h:108
urg_node::UrgNode::lockout_status_
bool lockout_status_
Definition: urg_node_driver.h:110
urg_node::UrgNode::addDiagnostics
void addDiagnostics()
Definition: urg_node_driver.cpp:283
urg_node::UrgNode::service_yield_
volatile bool service_yield_
Definition: urg_node_driver.h:130
urg_node::UrgNode::diagnostics_window_time_
double diagnostics_window_time_
Definition: urg_node_driver.h:127
urg_node::UrgNode::run
void run()
Start's the nodes threads to run the lidar.
Definition: urg_node_driver.cpp:640
publisher.h
urg_node::UrgNode::firmware_version_
std::string firmware_version_
Definition: urg_node_driver.h:105
diagnostic_updater.h
ros::ServiceServer
urg_node::UrgNode::initSetup
void initSetup()
Definition: urg_node_driver.cpp:62
bond.h
urg_c_wrapper.h
urg_node::UrgNode::ip_port_
int ip_port_
Definition: urg_node_driver.h:117
urg_node::UrgNode::device_status_
std::string device_status_
Definition: urg_node_driver.h:102
urg_node::UrgNode::vendor_name_
std::string vendor_name_
Definition: urg_node_driver.h:103
urg_node::UrgNode::status_service_
ros::ServiceServer status_service_
Definition: urg_node_driver.h:136
urg_node::UrgNode::pnh_
ros::NodeHandle pnh_
Definition: urg_node_driver.h:85
urg_node::UrgNode::laser_freq_
boost::shared_ptr< diagnostic_updater::HeaderlessTopicDiagnostic > laser_freq_
Definition: urg_node_driver.h:94
urg_node::UrgNode::freq_min_
double freq_min_
Definition: urg_node_driver.h:113
urg_node::UrgNode::echoes_freq_
boost::shared_ptr< diagnostic_updater::HeaderlessTopicDiagnostic > echoes_freq_
Definition: urg_node_driver.h:95
urg_node::UrgNode::serial_port_
std::string serial_port_
Definition: urg_node_driver.h:119
laser_proc::LaserPublisher
urg_node::UrgNode::ip_address_
std::string ip_address_
Definition: urg_node_driver.h:118
urg_node::UrgNode::reconfigure_callback
bool reconfigure_callback(urg_node::URGConfig &config, int level)
Definition: urg_node_driver.cpp:190
urg_node::UrgNode::firmware_date_
std::string firmware_date_
Definition: urg_node_driver.h:106
urg_node::UrgNode::echoes_pub_
laser_proc::LaserPublisher echoes_pub_
Definition: urg_node_driver.h:133
urg_node::UrgNode::close_diagnostics_
bool close_diagnostics_
Definition: urg_node_driver.h:114
urg_node::UrgNode::status_pub_
ros::Publisher status_pub_
Definition: urg_node_driver.h:134
diagnostic_updater::DiagnosticStatusWrapper
urg_node::UrgNode::srv_
boost::shared_ptr< dynamic_reconfigure::Server< urg_node::URGConfig > > srv_
Dynamic reconfigure server.
Definition: urg_node_driver.h:92
urg_node::UrgNode::synchronize_time_
bool synchronize_time_
Definition: urg_node_driver.h:122
urg_node::UrgNode::updateDiagnostics
void updateDiagnostics()
Definition: urg_node_driver.cpp:355
urg_node::UrgNode::calibrate_time_
bool calibrate_time_
Definition: urg_node_driver.h:121
urg_node::UrgNode::error_limit_
int error_limit_
Definition: urg_node_driver.h:125
urg_node::UrgNode::updateStatus
bool updateStatus()
Trigger an update of the lidar's status publish the latest known information about the lidar on latch...
Definition: urg_node_driver.cpp:118
urg_node::UrgNode::urg_
boost::shared_ptr< urg_node::URGCWrapper > urg_
Definition: urg_node_driver.h:91
urg_node
Definition: urg_c_wrapper.h:48
urg_node::UrgNode::populateDiagnosticsStatus
void populateDiagnosticsStatus(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: urg_node_driver.cpp:366
urg_node::UrgNode::error_code_
uint16_t error_code_
Definition: urg_node_driver.h:109
ros::NodeHandle
urg_node::UrgNode::detailed_status_
bool detailed_status_
Definition: urg_node_driver.h:128


urg_node
Author(s): Chad Rockey , Mike O'Driscoll
autogenerated on Fri Oct 14 2022 02:17:53