rsdriver.h
Go to the documentation of this file.
1 /* -*- mode: C++ -*- */
2 /*
3  * Copyright (C) 2012 Austin Robot Technology, Jack O'Quin
4  * Copyright (C) 2017 Robosense, Tony Zhang
5  *
6  * License: Modified BSD Software License Agreement
7  *
8 
9  Copyright (C) 2010-2013 Austin Robot Technology, and others
10  All rights reserved.
11 
12 
13 Modified BSD License:
14 --------------------
15 
16  Redistribution and use in source and binary forms, with or without
17  modification, are permitted provided that the following conditions
18  are met:
19 
20  * Redistributions of source code must retain the above copyright
21  notice, this list of conditions and the following disclaimer.
22 
23  * Redistributions in binary form must reproduce the above
24  copyright notice, this list of conditions and the following
25  disclaimer in the documentation and/or other materials provided
26  with the distribution.
27 
28  * Neither the names of the University of Texas at Austin, nor
29  Austin Robot Technology, nor the names of other contributors may
30  be used to endorse or promote products derived from this
31  software without specific prior written permission.
32 
33  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
34  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
35  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
36  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
37  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
38  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
39  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
40  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
41  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
42  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
43  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
44 POSSIBILITY OF SUCH DAMAGE.
45  */
46 
51 #ifndef _RSDRIVER_H_
52 #define _RSDRIVER_H_
53 
54 #include <string>
55 #include <ros/ros.h>
56 #include <ros/package.h>
59 #include <dynamic_reconfigure/server.h>
60 #include <rslidar_driver/rslidarNodeConfig.h>
61 #include <pcl/point_types.h>
64 #include "input.h"
65 
66 namespace rslidar_driver
67 {
69 {
70 public:
77 
79  {
80  }
81 
82  bool poll(void);
83  void difopPoll(void);
84 
85 private:
87  void callback(rslidar_driver::rslidarNodeConfig& config, uint32_t level);
88 
91 
92  // configuration parameters
93  struct
94  {
95  std::string frame_id;
96  std::string model;
97  int npackets;
98  double rpm;
99  double time_offset;
101  } config_;
102 
107  // Converter convtor_;
114 };
115 
116 } // namespace rslidar_driver
117 
118 #endif
diagnostic_updater::Updater diagnostics_
Definition: rsdriver.h:109
ros::Publisher difop_output_
Definition: rsdriver.h:106
rslidarDriver(ros::NodeHandle node, ros::NodeHandle private_nh)
rslidarDriver
Definition: rsdriver.cpp:56
ros::Publisher msop_output_
Definition: rsdriver.h:105
boost::shared_ptr< Input > msop_input_
Definition: rsdriver.h:103
int npackets
number of packets to collect
Definition: rsdriver.h:97
double time_offset
time in seconds added to each time stamp
Definition: rsdriver.h:99
struct rslidar_driver::rslidarDriver::@0 config_
std::string model
device model name
Definition: rsdriver.h:96
boost::shared_ptr< diagnostic_updater::TopicDiagnostic > diag_topic_
Definition: rsdriver.h:112
void callback(rslidar_driver::rslidarNodeConfig &config, uint32_t level)
Callback for dynamic reconfigure.
Definition: rsdriver.cpp:266
boost::shared_ptr< Input > difop_input_
Definition: rsdriver.h:104
std::string frame_id
tf frame ID
Definition: rsdriver.h:95
double rpm
device rotation rate (RPMs)
Definition: rsdriver.h:98
boost::shared_ptr< boost::thread > difop_thread_
Definition: rsdriver.h:113
boost::shared_ptr< dynamic_reconfigure::Server< rslidar_driver::rslidarNodeConfig > > srv_
Pointer to dynamic reconfigure service srv_.
Definition: rsdriver.h:90


rslidar_driver
Author(s): Tony Zhang , Tony Zhang
autogenerated on Mon Jun 10 2019 14:41:07