node.cpp
Go to the documentation of this file.
1 /*
2  * RPLIDAR ROS NODE
3  *
4  * Copyright (c) 2009 - 2014 RoboPeak Team
5  * http://www.robopeak.com
6  * Copyright (c) 2014 - 2016 Shanghai Slamtec Co., Ltd.
7  * http://www.slamtec.com
8  *
9  */
10 /*
11  * Redistribution and use in source and binary forms, with or without
12  * modification, are permitted provided that the following conditions are met:
13  *
14  * 1. Redistributions of source code must retain the above copyright notice,
15  * this list of conditions and the following disclaimer.
16  *
17  * 2. Redistributions in binary form must reproduce the above copyright notice,
18  * this list of conditions and the following disclaimer in the documentation
19  * and/or other materials provided with the distribution.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
23  * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
24  * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
25  * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
26  * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
27  * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS;
28  * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
29  * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR
30  * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
31  * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
32  *
33  */
34 
35 #include "ros/ros.h"
36 #include "sensor_msgs/LaserScan.h"
37 #include "std_srvs/Empty.h"
38 #include "rplidar.h"
39 
40 #ifndef _countof
41 #define _countof(_Array) (int)(sizeof(_Array) / sizeof(_Array[0]))
42 #endif
43 
44 #define DEG2RAD(x) ((x)*M_PI/180.)
45 
46 using namespace rp::standalone::rplidar;
47 
48 RPlidarDriver * drv = NULL;
49 
52  size_t node_count, ros::Time start,
53  double scan_time, bool inverted,
54  float angle_min, float angle_max,
55  float max_distance,
56  std::string frame_id)
57 {
58  static int scan_count = 0;
59  sensor_msgs::LaserScan scan_msg;
60 
61  scan_msg.header.stamp = start;
62  scan_msg.header.frame_id = frame_id;
63  scan_count++;
64 
65  bool reversed = (angle_max > angle_min);
66  if ( reversed ) {
67  scan_msg.angle_min = M_PI - angle_max;
68  scan_msg.angle_max = M_PI - angle_min;
69  } else {
70  scan_msg.angle_min = M_PI - angle_min;
71  scan_msg.angle_max = M_PI - angle_max;
72  }
73  scan_msg.angle_increment =
74  (scan_msg.angle_max - scan_msg.angle_min) / (double)(node_count-1);
75 
76  scan_msg.scan_time = scan_time;
77  scan_msg.time_increment = scan_time / (double)(node_count-1);
78  scan_msg.range_min = 0.15;
79  scan_msg.range_max = max_distance;//8.0;
80 
81  scan_msg.intensities.resize(node_count);
82  scan_msg.ranges.resize(node_count);
83  bool reverse_data = (!inverted && reversed) || (inverted && !reversed);
84  if (!reverse_data) {
85  for (size_t i = 0; i < node_count; i++) {
86  float read_value = (float) nodes[i].dist_mm_q2/4.0f/1000;
87  if (read_value == 0.0)
88  scan_msg.ranges[i] = std::numeric_limits<float>::infinity();
89  else
90  scan_msg.ranges[i] = read_value;
91  scan_msg.intensities[i] = (float) (nodes[i].quality >> 2);
92  }
93  } else {
94  for (size_t i = 0; i < node_count; i++) {
95  float read_value = (float)nodes[i].dist_mm_q2/4.0f/1000;
96  if (read_value == 0.0)
97  scan_msg.ranges[node_count-1-i] = std::numeric_limits<float>::infinity();
98  else
99  scan_msg.ranges[node_count-1-i] = read_value;
100  scan_msg.intensities[node_count-1-i] = (float) (nodes[i].quality >> 2);
101  }
102  }
103 
104  pub->publish(scan_msg);
105 }
106 
108 {
109  u_result op_result;
110  rplidar_response_device_info_t devinfo;
111 
112  op_result = drv->getDeviceInfo(devinfo);
113  if (IS_FAIL(op_result)) {
114  if (op_result == RESULT_OPERATION_TIMEOUT) {
115  ROS_ERROR("Error, operation time out. RESULT_OPERATION_TIMEOUT! ");
116  } else {
117  ROS_ERROR("Error, unexpected error, code: %x",op_result);
118  }
119  return false;
120  }
121 
122  // print out the device serial number, firmware and hardware version number..
123  printf("RPLIDAR S/N: ");
124  for (int pos = 0; pos < 16 ;++pos) {
125  printf("%02X", devinfo.serialnum[pos]);
126  }
127  printf("\n");
128  ROS_INFO("Firmware Ver: %d.%02d",devinfo.firmware_version>>8, devinfo.firmware_version & 0xFF);
129  ROS_INFO("Hardware Rev: %d",(int)devinfo.hardware_version);
130  return true;
131 }
132 
134 {
135  u_result op_result;
136  rplidar_response_device_health_t healthinfo;
137  op_result = drv->getHealth(healthinfo);
138  if (IS_OK(op_result)) {
139  ROS_INFO("RPLidar health status : %d", healthinfo.status);
140  if (healthinfo.status == RPLIDAR_STATUS_ERROR) {
141  ROS_ERROR("Error, rplidar internal error detected. Please reboot the device to retry.");
142  return false;
143  } else {
144  return true;
145  }
146 
147  } else {
148  ROS_ERROR("Error, cannot retrieve rplidar health code: %x", op_result);
149  return false;
150  }
151 }
152 
153 bool stop_motor(std_srvs::Empty::Request &req,
154  std_srvs::Empty::Response &res)
155 {
156  if(!drv)
157  return false;
158 
159  ROS_DEBUG("Stop motor");
160  drv->stopMotor();
161  return true;
162 }
163 
164 bool start_motor(std_srvs::Empty::Request &req,
165  std_srvs::Empty::Response &res)
166 {
167  if(!drv)
168  return false;
169  if(drv->isConnected())
170  {
171  ROS_DEBUG("Start motor");
172  u_result ans=drv->startMotor();
173 
174  ans=drv->startScan(0,1);
175  }
176  else ROS_INFO("lost connection");
177  return true;
178 }
179 
181 {
182  return node.angle_z_q14 * 90.f / 16384.f;
183 }
184 
185 int main(int argc, char * argv[]) {
186  ros::init(argc, argv, "rplidar_node");
187 
188  std::string channel_type;
189  std::string tcp_ip;
190  std::string serial_port;
191  int tcp_port = 20108;
192  int serial_baudrate = 115200;
193  std::string frame_id;
194  bool inverted = false;
195  bool angle_compensate = true;
196  float max_distance = 8.0;
197  int angle_compensate_multiple = 1;//it stand of angle compensate at per 1 degree
198  std::string scan_mode;
199  ros::NodeHandle nh;
200  ros::Publisher scan_pub = nh.advertise<sensor_msgs::LaserScan>("scan", 1000);
201  ros::NodeHandle nh_private("~");
202  nh_private.param<std::string>("channel_type", channel_type, "serial");
203  nh_private.param<std::string>("tcp_ip", tcp_ip, "192.168.0.7");
204  nh_private.param<int>("tcp_port", tcp_port, 20108);
205  nh_private.param<std::string>("serial_port", serial_port, "/dev/ttyUSB0");
206  nh_private.param<int>("serial_baudrate", serial_baudrate, 115200/*256000*/);//ros run for A1 A2, change to 256000 if A3
207  nh_private.param<std::string>("frame_id", frame_id, "laser_frame");
208  nh_private.param<bool>("inverted", inverted, false);
209  nh_private.param<bool>("angle_compensate", angle_compensate, false);
210  nh_private.param<std::string>("scan_mode", scan_mode, std::string());
211 
212  ROS_INFO("RPLIDAR running on ROS package rplidar_ros. SDK Version:"RPLIDAR_SDK_VERSION"");
213 
214  u_result op_result;
215 
216  // create the driver instance
217  if(channel_type == "tcp"){
219  }
220  else{
222  }
223 
224 
225  if (!drv) {
226  ROS_ERROR("Create Driver fail, exit");
227  return -2;
228  }
229 
230  if(channel_type == "tcp"){
231  // make connection...
232  if (IS_FAIL(drv->connect(tcp_ip.c_str(), (_u32)tcp_port))) {
233  ROS_ERROR("Error, cannot bind to the specified serial port %s.",serial_port.c_str());
235  return -1;
236  }
237 
238  }
239  else{
240  // make connection...
241  if (IS_FAIL(drv->connect(serial_port.c_str(), (_u32)serial_baudrate))) {
242  ROS_ERROR("Error, cannot bind to the specified serial port %s.",serial_port.c_str());
244  return -1;
245  }
246 
247  }
248 
249  // get rplidar device info
250  if (!getRPLIDARDeviceInfo(drv)) {
251  return -1;
252  }
253 
254  // check health...
255  if (!checkRPLIDARHealth(drv)) {
257  return -1;
258  }
259 
260  ros::ServiceServer stop_motor_service = nh.advertiseService("stop_motor", stop_motor);
261  ros::ServiceServer start_motor_service = nh.advertiseService("start_motor", start_motor);
262 
263  drv->startMotor();
264 
265  RplidarScanMode current_scan_mode;
266  if (scan_mode.empty()) {
267  op_result = drv->startScan(false /* not force scan */, true /* use typical scan mode */, 0, &current_scan_mode);
268  } else {
269  std::vector<RplidarScanMode> allSupportedScanModes;
270  op_result = drv->getAllSupportedScanModes(allSupportedScanModes);
271 
272  if (IS_OK(op_result)) {
273  _u16 selectedScanMode = _u16(-1);
274  for (std::vector<RplidarScanMode>::iterator iter = allSupportedScanModes.begin(); iter != allSupportedScanModes.end(); iter++) {
275  if (iter->scan_mode == scan_mode) {
276  selectedScanMode = iter->id;
277  break;
278  }
279  }
280 
281  if (selectedScanMode == _u16(-1)) {
282  ROS_ERROR("scan mode `%s' is not supported by lidar, supported modes:", scan_mode.c_str());
283  for (std::vector<RplidarScanMode>::iterator iter = allSupportedScanModes.begin(); iter != allSupportedScanModes.end(); iter++) {
284  ROS_ERROR("\t%s: max_distance: %.1f m, Point number: %.1fK", iter->scan_mode,
285  iter->max_distance, (1000/iter->us_per_sample));
286  }
287  op_result = RESULT_OPERATION_FAIL;
288  } else {
289  op_result = drv->startScanExpress(false /* not force scan */, selectedScanMode, 0, &current_scan_mode);
290  }
291  }
292  }
293 
294  if(IS_OK(op_result))
295  {
296  //default frequent is 10 hz (by motor pwm value), current_scan_mode.us_per_sample is the number of scan point per us
297  angle_compensate_multiple = (int)(1000*1000/current_scan_mode.us_per_sample/10.0/360.0);
298  if(angle_compensate_multiple < 1)
299  angle_compensate_multiple = 1;
300  max_distance = current_scan_mode.max_distance;
301  ROS_INFO("current scan mode: %s, max_distance: %.1f m, Point number: %.1fK , angle_compensate: %d", current_scan_mode.scan_mode,
302  current_scan_mode.max_distance, (1000/current_scan_mode.us_per_sample), angle_compensate_multiple);
303  }
304  else
305  {
306  ROS_ERROR("Can not start scan: %08x!", op_result);
307  }
308 
309  ros::Time start_scan_time;
310  ros::Time end_scan_time;
311  double scan_duration;
312  while (ros::ok()) {
314  size_t count = _countof(nodes);
315 
316  start_scan_time = ros::Time::now();
317  op_result = drv->grabScanDataHq(nodes, count);
318  end_scan_time = ros::Time::now();
319  scan_duration = (end_scan_time - start_scan_time).toSec();
320 
321  if (op_result == RESULT_OK) {
322  op_result = drv->ascendScanData(nodes, count);
323  float angle_min = DEG2RAD(0.0f);
324  float angle_max = DEG2RAD(359.0f);
325  if (op_result == RESULT_OK) {
326  if (angle_compensate) {
327  //const int angle_compensate_multiple = 1;
328  const int angle_compensate_nodes_count = 360*angle_compensate_multiple;
329  int angle_compensate_offset = 0;
330  rplidar_response_measurement_node_hq_t angle_compensate_nodes[angle_compensate_nodes_count];
331  memset(angle_compensate_nodes, 0, angle_compensate_nodes_count*sizeof(rplidar_response_measurement_node_hq_t));
332 
333  int i = 0, j = 0;
334  for( ; i < count; i++ ) {
335  if (nodes[i].dist_mm_q2 != 0) {
336  float angle = getAngle(nodes[i]);
337  int angle_value = (int)(angle * angle_compensate_multiple);
338  if ((angle_value - angle_compensate_offset) < 0) angle_compensate_offset = angle_value;
339  for (j = 0; j < angle_compensate_multiple; j++) {
340 
341  int angle_compensate_nodes_index = angle_value-angle_compensate_offset+j;
342  if(angle_compensate_nodes_index >= angle_compensate_nodes_count)
343  angle_compensate_nodes_index = angle_compensate_nodes_count-1;
344  angle_compensate_nodes[angle_compensate_nodes_index] = nodes[i];
345  }
346  }
347  }
348 
349  publish_scan(&scan_pub, angle_compensate_nodes, angle_compensate_nodes_count,
350  start_scan_time, scan_duration, inverted,
351  angle_min, angle_max, max_distance,
352  frame_id);
353  } else {
354  int start_node = 0, end_node = 0;
355  int i = 0;
356  // find the first valid node and last valid node
357  while (nodes[i++].dist_mm_q2 == 0);
358  start_node = i-1;
359  i = count -1;
360  while (nodes[i--].dist_mm_q2 == 0);
361  end_node = i+1;
362 
363  angle_min = DEG2RAD(getAngle(nodes[start_node]));
364  angle_max = DEG2RAD(getAngle(nodes[end_node]));
365 
366  publish_scan(&scan_pub, &nodes[start_node], end_node-start_node +1,
367  start_scan_time, scan_duration, inverted,
368  angle_min, angle_max, max_distance,
369  frame_id);
370  }
371  } else if (op_result == RESULT_OPERATION_FAIL) {
372  // All the data is invalid, just publish them
373  float angle_min = DEG2RAD(0.0f);
374  float angle_max = DEG2RAD(359.0f);
375  publish_scan(&scan_pub, nodes, count,
376  start_scan_time, scan_duration, inverted,
377  angle_min, angle_max, max_distance,
378  frame_id);
379  }
380  }
381 
382  ros::spinOnce();
383  }
384 
385  // done!
386  drv->stopMotor();
387  drv->stop();
389  return 0;
390 }
_u32 dist_mm_q2
Definition: rplidar_cmd.h:3
#define IS_OK(x)
Definition: rptypes.h:113
virtual u_result stop(_u32 timeout=DEFAULT_TIMEOUT)=0
void publish(const boost::shared_ptr< M > &message) const
bool getRPLIDARDeviceInfo(RPlidarDriver *drv)
Definition: node.cpp:107
f
int main(int argc, char *argv[])
Definition: node.cpp:185
virtual u_result grabScanDataHq(rplidar_response_measurement_node_hq_t *nodebuffer, size_t &count, _u32 timeout=DEFAULT_TIMEOUT)=0
bool stop_motor(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Definition: node.cpp:153
_u8 quality
Definition: rplidar_cmd.h:4
void publish_scan(ros::Publisher *pub, rplidar_response_measurement_node_hq_t *nodes, size_t node_count, ros::Time start, double scan_time, bool inverted, float angle_min, float angle_max, float max_distance, std::string frame_id)
Definition: node.cpp:50
static void DisposeDriver(RPlidarDriver *drv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
virtual u_result startScanExpress(bool force, _u16 scanMode, _u32 options=0, RplidarScanMode *outUsedScanMode=NULL, _u32 timeout=DEFAULT_TIMEOUT)=0
#define RESULT_OK
Definition: rptypes.h:102
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
virtual u_result stopMotor()=0
Stop RPLIDAR&#39;s motor when using accessory board.
#define RPLIDAR_STATUS_ERROR
Definition: rplidar_cmd.h:145
virtual u_result startMotor()=0
Start RPLIDAR&#39;s motor when using accessory board.
#define IS_FAIL(x)
Definition: rptypes.h:114
#define RPLIDAR_SDK_VERSION
Definition: rplidar.h:44
#define DEG2RAD(x)
Definition: node.cpp:44
#define ROS_INFO(...)
#define _countof(_Array)
Definition: node.cpp:41
ROSCPP_DECL bool ok()
#define RESULT_OPERATION_TIMEOUT
Definition: rptypes.h:107
virtual u_result startScan(bool force, bool useTypicalScan, _u32 options=0, RplidarScanMode *outUsedScanMode=NULL)=0
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
virtual u_result ascendScanData(rplidar_response_measurement_node_hq_t *nodebuffer, size_t count)=0
virtual u_result getAllSupportedScanModes(std::vector< RplidarScanMode > &outModes, _u32 timeoutInMs=DEFAULT_TIMEOUT)=0
Get all scan modes that supported by lidar.
virtual u_result getDeviceInfo(rplidar_response_device_info_t &info, _u32 timeout=DEFAULT_TIMEOUT)=0
uint32_t _u32
Definition: rptypes.h:69
static float getAngle(const rplidar_response_measurement_node_t &node)
static RPlidarDriver * CreateDriver(_u32 drivertype=DRIVER_TYPE_SERIALPORT)
virtual bool isConnected()=0
Returns TRUE when the connection has been established.
#define RESULT_OPERATION_FAIL
Definition: rptypes.h:106
static Time now()
bool start_motor(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Definition: node.cpp:164
virtual u_result connect(const char *, _u32, _u32 flag=0)=0
uint16_t _u16
Definition: rptypes.h:66
ROSCPP_DECL void spinOnce()
#define ROS_ERROR(...)
bool checkRPLIDARHealth(RPlidarDriver *drv)
Definition: node.cpp:133
RPlidarDriver * drv
Definition: node.cpp:48
virtual u_result getHealth(rplidar_response_device_health_t &health, _u32 timeout=DEFAULT_TIMEOUT)=0
uint32_t u_result
Definition: rptypes.h:100
#define ROS_DEBUG(...)


rplidar_ros
Author(s):
autogenerated on Wed Jan 1 2020 04:01:40