urg_c_wrapper.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2013, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 /*
31  * Author: Chad Rockey
32  */
33 
34 #ifndef URG_NODE_URG_C_WRAPPER_H
35 #define URG_NODE_URG_C_WRAPPER_H
36 
37 #include <stdexcept>
38 #include <sstream>
39 #include <vector>
40 #include <string>
41 
42 #include <sensor_msgs/LaserScan.h>
43 #include <sensor_msgs/MultiEchoLaserScan.h>
44 
45 #include <urg_c/urg_sensor.h>
46 #include <urg_c/urg_utils.h>
47 
48 namespace urg_node
49 {
50 
51 class URGStatus
52 {
53 public:
55  {
56  status = 0;
57  operating_mode = 0;
58  area_number = 0;
59  error_status = false;
60  error_code = 0;
61  lockout_status = false;
62  }
63 
64  uint16_t status;
65  uint16_t operating_mode;
66  uint16_t area_number;
68  uint16_t error_code;
70 };
71 
73 {
74 public:
76  {
77  status = 0;
78  area = 0;
79  distance = 0;
80  angle = 0;
81  }
82 
83  uint16_t status;
84  uint16_t area;
85  uint16_t distance;
86  float angle;
87 };
88 
90 {
91 public:
92  URGCWrapper(const std::string& ip_address, const int ip_port,
93  bool& using_intensity, bool& using_multiecho, bool synchronize_time);
94 
95  URGCWrapper(const int serial_baud, const std::string& serial_port,
96  bool& using_intensity, bool& using_multiecho, bool synchronize_time);
97 
98  ~URGCWrapper();
99 
100  void start();
101 
102  void stop();
103 
104  bool isStarted() const;
105 
106  double getRangeMin() const;
107 
108  double getRangeMax() const;
109 
110  double getAngleMin() const;
111 
112  double getAngleMax() const;
113 
114  double getAngleMinLimit() const;
115 
116  double getAngleMaxLimit() const;
117 
118  double getAngleIncrement() const;
119 
120  double getScanPeriod() const;
121 
122  double getTimeIncrement() const;
123 
124  std::string getIPAddress() const;
125 
126  int getIPPort() const;
127 
128  std::string getSerialPort() const;
129 
130  int getSerialBaud() const;
131 
132  std::string getVendorName();
133 
134  std::string getProductName();
135 
136  std::string getFirmwareVersion();
137 
138  std::string getFirmwareDate();
139 
140  std::string getProtocolVersion();
141 
142  std::string getDeviceID();
143 
144  ros::Duration getComputedLatency() const;
145 
146  ros::Duration getUserTimeOffset() const;
147 
148  std::string getSensorStatus();
149 
150  std::string getSensorState();
151 
152  void setFrameId(const std::string& frame_id);
153 
154  void setUserLatency(const double latency);
155 
156  bool setAngleLimitsAndCluster(double& angle_min, double& angle_max, int cluster);
157 
158  bool setSkip(int skip);
159 
160  ros::Duration computeLatency(size_t num_measurements);
161 
162  bool grabScan(const sensor_msgs::LaserScanPtr& msg);
163 
164  bool grabScan(const sensor_msgs::MultiEchoLaserScanPtr& msg);
165 
166  bool getAR00Status(URGStatus& status);
167 
168  bool getDL00Status(UrgDetectionReport& report);
169 
170 private:
171  void initialize(bool& using_intensity, bool& using_multiecho, bool synchronize_time);
172 
173  bool isIntensitySupported();
174 
175  bool isMultiEchoSupported();
176 
177  ros::Duration getAngularTimeOffset() const;
178 
179  ros::Duration getNativeClockOffset(size_t num_measurements);
180 
181  ros::Duration getTimeStampOffset(size_t num_measurements);
182 
189  ros::Time getSynchronizedTime(long time_stamp, long long system_time_stamp);
190 
195  bool setToSCIP2();
196 
203  uint16_t checkCRC(const char* bytes, const uint32_t size);
204 
211  std::string sendCommand(std::string cmd);
212 
213  std::string frame_id_;
214 
216  bool started_;
217 
218  std::vector<long> data_;
219  std::vector<unsigned short> intensity_;
220 
226  int cluster_;
227  int skip_;
228 
231 
232  // used for clock synchronziation
237  const double adj_alpha_ = .01;
238  uint64_t adj_count_;
239 
240  std::string ip_address_;
241  int ip_port_;
242  std::string serial_port_;
244 };
245 } // namespace urg_node
246 
247 #endif // URG_NODE_URG_C_WRAPPER_H
msg
ros::Duration user_latency_
ROSCONSOLE_DECL void initialize()
string cmd
urg_measurement_type_t
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
urg_measurement_type_t measurement_type_
std::string serial_port_
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
std::vector< unsigned short > intensity_
std::vector< long > data_
ros::Duration system_latency_
std::string frame_id_
Output frame_id for each laserscan.


urg_node
Author(s): Chad Rockey , Mike O'Driscoll
autogenerated on Wed Jun 5 2019 19:29:02