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 
145 
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  void 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 
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
urg_node::URGCWrapper::getAngleMax
double getAngleMax() const
Definition: urg_c_wrapper.cpp:695
urg_node::URGCWrapper::use_intensity_
bool use_intensity_
Definition: urg_c_wrapper.h:221
urg_t
urg_node::URGCWrapper::getVendorName
std::string getVendorName()
Definition: urg_c_wrapper.cpp:760
urg_node::URGCWrapper::adj_count_
uint64_t adj_count_
Definition: urg_c_wrapper.h:238
urg_node::URGStatus
Definition: urg_c_wrapper.h:51
urg_node::URGCWrapper::getProtocolVersion
std::string getProtocolVersion()
Definition: urg_c_wrapper.cpp:780
msg
msg
urg_node::URGCWrapper::isMultiEchoSupported
bool isMultiEchoSupported()
Definition: urg_c_wrapper.cpp:890
urg_node::URGCWrapper::getSynchronizedTime
ros::Time getSynchronizedTime(long time_stamp, long long system_time_stamp)
Get synchronized time stamp using hardware clock.
Definition: urg_c_wrapper.cpp:1052
urg_node::URGCWrapper::urg_
urg_t urg_
Definition: urg_c_wrapper.h:215
urg_node::URGCWrapper::getTimeStampOffset
ros::Duration getTimeStampOffset(size_t num_measurements)
Definition: urg_c_wrapper.cpp:994
urg_node::URGCWrapper::first_step_
int first_step_
Definition: urg_c_wrapper.h:224
urg_node::URGCWrapper::data_
std::vector< long > data_
Definition: urg_c_wrapper.h:218
urg_node::URGCWrapper
Definition: urg_c_wrapper.h:89
urg_node::URGStatus::lockout_status
bool lockout_status
Definition: urg_c_wrapper.h:69
urg_node::URGCWrapper::getFirmwareVersion
std::string getFirmwareVersion()
Definition: urg_c_wrapper.cpp:770
urg_node::URGCWrapper::serial_port_
std::string serial_port_
Definition: urg_c_wrapper.h:242
urg_node::URGCWrapper::getProductName
std::string getProductName()
Definition: urg_c_wrapper.cpp:765
urg_node::URGCWrapper::ip_port_
int ip_port_
Definition: urg_c_wrapper.h:241
urg_node::URGCWrapper::skip_
int skip_
Definition: urg_c_wrapper.h:227
urg_node::URGCWrapper::frame_id_
std::string frame_id_
Output frame_id for each laserscan.
Definition: urg_c_wrapper.h:213
urg_node::URGCWrapper::getFirmwareDate
std::string getFirmwareDate()
Definition: urg_c_wrapper.cpp:775
urg_node::URGCWrapper::getNativeClockOffset
ros::Duration getNativeClockOffset(size_t num_measurements)
Definition: urg_c_wrapper.cpp:953
urg_node::URGCWrapper::isStarted
bool isStarted() const
Definition: urg_c_wrapper.cpp:669
urg_node::URGCWrapper::getDeviceID
std::string getDeviceID()
Definition: urg_c_wrapper.cpp:785
urg_node::URGStatus::URGStatus
URGStatus()
Definition: urg_c_wrapper.h:54
urg_node::URGCWrapper::isIntensitySupported
bool isIntensitySupported()
Definition: urg_c_wrapper.cpp:873
urg_node::URGCWrapper::getRangeMin
double getRangeMin() const
Definition: urg_c_wrapper.cpp:674
urg_node::URGStatus::error_status
bool error_status
Definition: urg_c_wrapper.h:67
urg_node::URGCWrapper::setFrameId
void setFrameId(const std::string &frame_id)
Definition: urg_c_wrapper.cpp:810
urg_node::URGCWrapper::sendCommand
std::string sendCommand(std::string cmd)
Send an arbitrary serial command to the lidar. These commands can also be sent via the ethernet socke...
Definition: urg_c_wrapper.cpp:579
urg_node::URGCWrapper::getAR00Status
bool getAR00Status(URGStatus &status)
Definition: urg_c_wrapper.cpp:342
urg_utils.h
urg_node::URGCWrapper::last_step_
int last_step_
Definition: urg_c_wrapper.h:225
urg_node::URGCWrapper::getSensorState
std::string getSensorState()
Definition: urg_c_wrapper.cpp:805
urg_node::URGCWrapper::hardware_clock_
double hardware_clock_
Definition: urg_c_wrapper.h:234
urg_node::URGStatus::area_number
uint16_t area_number
Definition: urg_c_wrapper.h:66
urg_node::URGCWrapper::ip_address_
std::string ip_address_
Definition: urg_c_wrapper.h:240
urg_node::URGCWrapper::getIPAddress
std::string getIPAddress() const
Definition: urg_c_wrapper.cpp:740
urg_node::URGCWrapper::setUserLatency
void setUserLatency(const double latency)
Definition: urg_c_wrapper.cpp:815
urg_node::UrgDetectionReport::status
uint16_t status
Definition: urg_c_wrapper.h:83
urg_node::URGCWrapper::getSerialPort
std::string getSerialPort() const
Definition: urg_c_wrapper.cpp:750
urg_node::URGCWrapper::stop
void stop()
Definition: urg_c_wrapper.cpp:194
urg_node::URGCWrapper::setToSCIP2
bool setToSCIP2()
Set the Hokuyo URG-04LX from SCIP 1.1 mode to SCIP 2.0 mode.
Definition: urg_c_wrapper.cpp:545
urg_node::URGCWrapper::getRangeMax
double getRangeMax() const
Definition: urg_c_wrapper.cpp:682
urg_node::URGCWrapper::checkCRC
uint16_t checkCRC(const char *bytes, const uint32_t size)
calculate the crc of a given set of bytes.
Definition: urg_c_wrapper.cpp:572
urg_node::URGStatus::operating_mode
uint16_t operating_mode
Definition: urg_c_wrapper.h:65
urg_node::URGCWrapper::setSkip
void setSkip(int skip)
Definition: urg_c_wrapper.cpp:868
urg_node::URGCWrapper::hardware_clock_adj_
double hardware_clock_adj_
Definition: urg_c_wrapper.h:236
urg_node::URGCWrapper::getSerialBaud
int getSerialBaud() const
Definition: urg_c_wrapper.cpp:755
urg_node::UrgDetectionReport::area
uint16_t area
Definition: urg_c_wrapper.h:84
urg_node::URGCWrapper::serial_baud_
int serial_baud_
Definition: urg_c_wrapper.h:243
urg_node::URGCWrapper::getTimeIncrement
double getTimeIncrement() const
Definition: urg_c_wrapper.cpp:729
urg_measurement_type_t
urg_measurement_type_t
urg_node::URGCWrapper::getDL00Status
bool getDL00Status(UrgDetectionReport &report)
Definition: urg_c_wrapper.cpp:432
urg_node::URGCWrapper::system_latency_
ros::Duration system_latency_
Definition: urg_c_wrapper.h:229
urg_node::URGStatus::status
uint16_t status
Definition: urg_c_wrapper.h:64
urg_node::URGCWrapper::setAngleLimitsAndCluster
bool setAngleLimitsAndCluster(double &angle_min, double &angle_max, int cluster)
Definition: urg_c_wrapper.cpp:821
urg_node::UrgDetectionReport::angle
float angle
Definition: urg_c_wrapper.h:86
urg_node::UrgDetectionReport
Definition: urg_c_wrapper.h:72
urg_node::URGCWrapper::user_latency_
ros::Duration user_latency_
Definition: urg_c_wrapper.h:230
urg_node::URGCWrapper::getSensorStatus
std::string getSensorStatus()
Definition: urg_c_wrapper.cpp:800
ros::Time
urg_node::URGCWrapper::getUserTimeOffset
ros::Duration getUserTimeOffset() const
Definition: urg_c_wrapper.cpp:795
urg_node::URGCWrapper::getIPPort
int getIPPort() const
Definition: urg_c_wrapper.cpp:745
urg_node::UrgDetectionReport::distance
uint16_t distance
Definition: urg_c_wrapper.h:85
urg_node::URGCWrapper::start
void start()
Definition: urg_c_wrapper.cpp:170
urg_node::URGCWrapper::getAngleMaxLimit
double getAngleMaxLimit() const
Definition: urg_c_wrapper.cpp:708
urg_node::URGCWrapper::getAngleMinLimit
double getAngleMinLimit() const
Definition: urg_c_wrapper.cpp:700
urg_node::URGCWrapper::computeLatency
ros::Duration computeLatency(size_t num_measurements)
Definition: urg_c_wrapper.cpp:923
urg_node::URGCWrapper::grabScan
bool grabScan(const sensor_msgs::LaserScanPtr &msg)
Definition: urg_c_wrapper.cpp:206
urg_node::URGCWrapper::getComputedLatency
ros::Duration getComputedLatency() const
Definition: urg_c_wrapper.cpp:790
urg_node::URGCWrapper::measurement_type_
urg_measurement_type_t measurement_type_
Definition: urg_c_wrapper.h:223
urg_node::URGCWrapper::getAngleMin
double getAngleMin() const
Definition: urg_c_wrapper.cpp:690
urg_node::URGCWrapper::URGCWrapper
URGCWrapper(const std::string &ip_address, const int ip_port, bool &using_intensity, bool &using_multiecho, bool synchronize_time)
Definition: urg_c_wrapper.cpp:44
urg_sensor.h
urg_node::URGCWrapper::getAngularTimeOffset
ros::Duration getAngularTimeOffset() const
Definition: urg_c_wrapper.cpp:907
cmd
string cmd
urg_node::URGCWrapper::getScanPeriod
double getScanPeriod() const
Definition: urg_c_wrapper.cpp:723
urg_node::URGCWrapper::started_
bool started_
Definition: urg_c_wrapper.h:216
urg_node::URGCWrapper::intensity_
std::vector< unsigned short > intensity_
Definition: urg_c_wrapper.h:219
urg_node::URGCWrapper::adj_alpha_
const double adj_alpha_
Definition: urg_c_wrapper.h:237
urg_node::URGStatus::error_code
uint16_t error_code
Definition: urg_c_wrapper.h:68
ros::Duration
urg_node::URGCWrapper::initialize
void initialize(bool &using_intensity, bool &using_multiecho, bool synchronize_time)
Definition: urg_c_wrapper.cpp:97
urg_node
Definition: urg_c_wrapper.h:48
urg_node::UrgDetectionReport::UrgDetectionReport
UrgDetectionReport()
Definition: urg_c_wrapper.h:75
urg_node::URGCWrapper::cluster_
int cluster_
Definition: urg_c_wrapper.h:226
urg_node::URGCWrapper::~URGCWrapper
~URGCWrapper()
Definition: urg_c_wrapper.cpp:200
urg_node::URGCWrapper::use_multiecho_
bool use_multiecho_
Definition: urg_c_wrapper.h:222
urg_node::URGCWrapper::last_hardware_time_stamp_
long last_hardware_time_stamp_
Definition: urg_c_wrapper.h:235
urg_node::URGCWrapper::getAngleIncrement
double getAngleIncrement() const
Definition: urg_c_wrapper.cpp:716
urg_node::URGCWrapper::synchronize_time_
bool synchronize_time_
Definition: urg_c_wrapper.h:233


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