YARP
Yet Another Robot Platform
rpLidar.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2006-2020 Istituto Italiano di Tecnologia (IIT)
3  *
4  * This library is free software; you can redistribute it and/or
5  * modify it under the terms of the GNU Lesser General Public
6  * License as published by the Free Software Foundation; either
7  * version 2.1 of the License, or (at your option) any later version.
8  *
9  * This library is distributed in the hope that it will be useful,
10  * but WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
12  * Lesser General Public License for more details.
13  *
14  * You should have received a copy of the GNU Lesser General Public
15  * License along with this library; if not, write to the Free Software
16  * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA
17  */
18 
19 #define _USE_MATH_DEFINES
20 
21 #include "rpLidar.h"
22 
23 #include <yarp/os/Time.h>
24 #include <yarp/os/Log.h>
25 #include <yarp/os/LogStream.h>
26 #include <yarp/os/ResourceFinder.h>
27 
28 #include <cmath>
29 #include <cstdlib>
30 #include <cstring>
31 #include <iostream>
32 #include <limits>
33 #include <mutex>
34 
35 
36 //#define LASER_DEBUG
37 //#define FORCE_SCAN
38 
39 using namespace std;
40 
41 #ifndef DEG2RAD
42 #define DEG2RAD M_PI/180.0
43 #endif
44 
45 YARP_LOG_COMPONENT(RPLIDAR, "yarp.device.rpLidar")
46 
48 {
49  maxsize = bufferSize + 1;
50  start = 0;
51  end = 0;
52  elems = (byte *)calloc(maxsize, sizeof(byte));
53 }
54 
56 {
57  free(elems);
58 }
59 
60 //-------------------------------------------------------------------------------------
61 
63 {
64  info = "Fake Laser device for test/debugging";
65  device_status = DEVICE_OK_STANBY;
66 
67 #ifdef LASER_DEBUG
68  yCDebug(RPLIDAR, "%s\n", config.toString().c_str());
69 #endif
70 
71  min_distance = 0.1; //m
72  max_distance = 2.5; //m
73 
74  bool br = config.check("GENERAL");
75  if (br != false)
76  {
77  yarp::os::Searchable& general_config = config.findGroup("GENERAL");
78  clip_max_enable = general_config.check("clip_max");
79  clip_min_enable = general_config.check("clip_min");
80  if (clip_max_enable) { max_distance = general_config.find("clip_max").asFloat64(); }
81  if (clip_min_enable) { min_distance = general_config.find("clip_min").asFloat64(); }
82  if (general_config.check("max_angle") == false) { yCError(RPLIDAR) << "Missing max_angle param"; return false; }
83  if (general_config.check("min_angle") == false) { yCError(RPLIDAR) << "Missing min_angle param"; return false; }
84  if (general_config.check("resolution") == false) { yCError(RPLIDAR) << "Missing resolution param"; return false; }
85  max_angle = general_config.find("max_angle").asFloat64();
86  min_angle = general_config.find("min_angle").asFloat64();
87  resolution = general_config.find("resolution").asFloat64();
88  do_not_clip_infinity_enable = (general_config.find("allow_infinity").asInt32()!=0);
89  }
90  else
91  {
92  yCError(RPLIDAR) << "Missing GENERAL section";
93  return false;
94  }
95 
96  bool bs = config.check("SKIP");
97  if (bs != false)
98  {
99  yarp::os::Searchable& skip_config = config.findGroup("SKIP");
100  Bottle mins = skip_config.findGroup("min");
101  Bottle maxs = skip_config.findGroup("max");
102  size_t s_mins = mins.size();
103  size_t s_maxs = mins.size();
104  if (s_mins == s_maxs && s_maxs > 1 )
105  {
106  for (size_t s = 1; s < s_maxs; s++)
107  {
108  Range_t range;
109  range.max = maxs.get(s).asFloat64();
110  range.min = mins.get(s).asFloat64();
111  if (range.max >= 0 && range.max <= 360 &&
112  range.min >= 0 && range.min <= 360 &&
113  range.max > range.min)
114  {
115  range_skip_vector.push_back(range);
116  }
117  else
118  {
119  yCError(RPLIDAR) << "Invalid range in SKIP section";
120  return false;
121  }
122  }
123  }
124 
125  }
126 
127  if (max_angle <= min_angle) { yCError(RPLIDAR) << "max_angle should be > min_angle"; return false; }
128  double fov = (max_angle - min_angle);
129  if (fov >360) { yCError(RPLIDAR) << "max_angle - min_angle <= 360"; return false; }
130  sensorsNum = (int)(fov/resolution);
131  laser_data.resize(sensorsNum,0.0);
132 
133  yCInfo(RPLIDAR, "Starting debug mode");
134  yCInfo(RPLIDAR, "max_dist %f, min_dist %f", max_distance, min_distance);
135  yCInfo(RPLIDAR, "max_angle %f, min_angle %f", max_angle, min_angle);
136  yCInfo(RPLIDAR, "resolution %f", resolution);
137  yCInfo(RPLIDAR, "sensors %d", sensorsNum);
138 
139  yarp::os::Searchable& general_config = config.findGroup("GENERAL");
140  bool ok = general_config.check("Serial_Configuration");
141  if (!ok)
142  {
143  yCError(RPLIDAR, "Cannot find configuration file for serial port communication!");
144  return false;
145  }
146  std::string serial_filename = general_config.find("Serial_Configuration").asString();
147 
148  Property prop;
149  ResourceFinder rf;
150  std::string serial_completefilename= rf.findFileByName(serial_filename);
151 
152  prop.put("device", "serialport");
153  ok = prop.fromConfigFile(serial_completefilename, config, false);
154  if (!ok)
155  {
156  yCError(RPLIDAR, "Unable to read from serial port configuration file");
157  return false;
158  }
159 
160  pSerial = nullptr;
161  driver.open(prop);
162  if (!driver.isValid())
163  {
164  yCError(RPLIDAR, "Error opening PolyDriver check parameters");
165  return false;
166  }
167  driver.view(pSerial);
168  if (!pSerial)
169  {
170  yCError(RPLIDAR, "Error opening serial driver. Device not available");
171  return false;
172  }
173 
174  //
175  int cleanup = pSerial->flush();
176  if (cleanup > 0)
177  {
178  yCDebug(RPLIDAR, "cleanup performed, flushed %d chars", cleanup);
179  }
180 
181  // check health
182  bool b_health = HW_getHealth();
183  if (b_health == false)
184  {
185  yCWarning(RPLIDAR, "Sensor in error status, attempt to recover");
186  HW_reset();
187  b_health = HW_getHealth();
188  if (b_health == false)
189  {
190  yCError(RPLIDAR, "Unable to recover error");
191  return false;
192  }
193  else
194  {
195  yCInfo(RPLIDAR, "Sensor recovered from a previous error status");
196  }
197  }
198  yCInfo(RPLIDAR, "Sensor ready");
199 
200 // string info;
201 // bool b_info = HW_getInfo(info);
202 
203  return PeriodicThread::start();
204 }
205 
207 {
208  PeriodicThread::stop();
209 
210  if (!HW_stop())
211  {
212  yCError(RPLIDAR, "Unable to stop sensor!");
213  HW_reset();
214  }
215 
216  if(driver.isValid())
217  driver.close();
218 
219  yCInfo(RPLIDAR) << "rpLidar closed";
220  return true;
221 }
222 
223 bool RpLidar::getDistanceRange(double& min, double& max)
224 {
225  std::lock_guard<std::mutex> guard(mutex);
226  min = min_distance;
227  max = max_distance;
228  return true;
229 }
230 
231 bool RpLidar::setDistanceRange(double min, double max)
232 {
233  std::lock_guard<std::mutex> guard(mutex);
234  min_distance = min;
235  max_distance = max;
236  return true;
237 }
238 
239 bool RpLidar::getScanLimits(double& min, double& max)
240 {
241  std::lock_guard<std::mutex> guard(mutex);
242  min = min_angle;
243  max = max_angle;
244  return true;
245 }
246 
247 bool RpLidar::setScanLimits(double min, double max)
248 {
249  std::lock_guard<std::mutex> guard(mutex);
250  min_angle = min;
251  max_angle = max;
252  return true;
253 }
254 
256 {
257  std::lock_guard<std::mutex> guard(mutex);
258  step = resolution;
259  return true;
260 }
261 
263 {
264  std::lock_guard<std::mutex> guard(mutex);
265  resolution = step;
266  return true;
267 }
268 
269 bool RpLidar::getScanRate(double& rate)
270 {
271  std::lock_guard<std::mutex> guard(mutex);
272  yCWarning(RPLIDAR, "getScanRate not yet implemented");
273  return true;
274 }
275 
276 bool RpLidar::setScanRate(double rate)
277 {
278  std::lock_guard<std::mutex> guard(mutex);
279  yCWarning(RPLIDAR, "setScanRate not yet implemented");
280  return false;
281 }
282 
283 
285 {
286  std::lock_guard<std::mutex> guard(mutex);
287  out = laser_data;
289  return true;
290 }
291 
292 bool RpLidar::getLaserMeasurement(std::vector<LaserMeasurementData> &data)
293 {
294  std::lock_guard<std::mutex> guard(mutex);
295 #ifdef LASER_DEBUG
296  //yCDebug(RPLIDAR, "data: %s\n", laser_data.toString().c_str());
297 #endif
298  size_t size = laser_data.size();
299  data.resize(size);
300  if (max_angle < min_angle) { yCError(RPLIDAR) << "getLaserMeasurement failed"; return false; }
301  double laser_angle_of_view = max_angle - min_angle;
302  for (size_t i = 0; i < size; i++)
303  {
304  double angle = (i / double(size)*laser_angle_of_view + min_angle)* DEG2RAD;
305  data[i].set_polar(laser_data[i], angle);
306  }
308  return true;
309 }
311 {
312  std::lock_guard<std::mutex> guard(mutex);
313  status = device_status;
314  return true;
315 }
316 
318 {
319 #ifdef LASER_DEBUG
320  yCDebug(RPLIDAR, "RpLidar:: thread initialising...\n");
321  yCDebug(RPLIDAR, "... done!\n");
322 #endif
323 
324  if (!HW_start())
325  {
326  yCError(RPLIDAR, "Unable to put sensor in scan mode!");
327  return false;
328  }
329  return true;
330 }
331 
332 bool RpLidar::HW_getInfo(string& s_info)
333 {
334  int r = 0;
335  unsigned char cmd_arr[2];
336  cmd_arr[0] = 0xA5;
337  cmd_arr[1] = 0x50;
338  pSerial->send((char *)cmd_arr, 2);
339 
341 
342  unsigned char s[255];
343  r = pSerial->receiveBytes(s, 7);
344  if (r!=7)
345  {
346  yCError(RPLIDAR, "Received answer with wrong length: %d", r);
347  return false;
348  }
349 
350  if ((unsigned char)s[0] != 0xA5 || (unsigned char)s[1] != 0x5A || (unsigned char)s[2] != 0x14 || (unsigned char)s[6] != 0x04)
351  {
352  yCError(RPLIDAR, "Invalid answer header");
353  return false;
354  }
355 
356  r = pSerial->receiveBytes(s, 20);
357  if (r!=20)
358  {
359  yCError(RPLIDAR, "Received answer with wrong length: %d", r);
360  return false;
361  }
362  char info[512];
363  sprintf(info, "model %d fw_major %d fw_minor %d hardware %d serial number %c%c%c%c%c %c%c%c%c%c %c%c%c%c%c%c",
364  s[0], s[1], s[2], s[3],
365  s[4], s[5], s[6], s[7], s[8],
366  s[9], s[10], s[11], s[12], s[13],
367  s[14], s[15], s[16], s[17], s[18], s[19]);
368  s_info.append(info);
369  return true;
370 }
371 
372 bool RpLidar::HW_getHealth()
373 {
374  pSerial->flush();
375 
376  int r = 0;
377  unsigned char cmd_arr[2];
378  cmd_arr[0] = 0xA5;
379  cmd_arr[1] = 0x52;
380  pSerial->send((char *)cmd_arr, 2);
381 
383 
384  unsigned char s[255];
385  memset(s, 0, 255);
386  r = pSerial->receiveBytes(s,7);
387  if (r!=7)
388  {
389  yCError(RPLIDAR, "Received answer with wrong length: %d", r);
390  return false;
391  }
392 
393  if ((unsigned char)s[0] != 0xA5 || (unsigned char)s[1] != 0x5A || (unsigned char)s[2] != 3 || (unsigned char)s[6] != 0x06)
394  {
395  yCError(RPLIDAR, "Invalid answer header");
396  return false;
397  }
398 
399  memset(s, 0, 255);
400  r = pSerial->receiveBytes(s,3);
401  if (r !=3)
402  {
403  yCError(RPLIDAR, "Received answer with wrong length: %d", r);
404  return false;
405  }
406 
407  int status = s[0];
408  int code = s[1] << 8 | s[2];
409  if (status == 0)
410  {
411  return true;
412  }
413  else if (status == 1)
414  {
415  yCWarning(RPLIDAR, "sensor in warning status, code %d", code);
416  return true;
417  }
418  else if (status == 2)
419  {
420  yCError(RPLIDAR, "sensor in error status, code %d", code);
421  return true;
422  }
423  yCError(RPLIDAR, "Unkwnon answer code");
424  return false;
425 }
426 
427 bool RpLidar::HW_reset()
428 {
429  pSerial->flush();
430 
431  unsigned char cmd_arr[2];
432  cmd_arr[0] = 0xA5;
433  cmd_arr[1] = 0x40;
434  pSerial->send((char *)cmd_arr, 2);
435 
437  return true;
438 }
439 
440 bool RpLidar::HW_start()
441 {
442  pSerial->flush();
443 
444  int r = 0;
445 
446  unsigned char cmd_arr[2];
447  cmd_arr[0] = 0xA5;
448 #ifdef FORCE_SCAN
449  cmd_arr[1] = 0x21;
450 #else
451  cmd_arr[1] = 0x20;
452 #endif
453  pSerial->send((char *)cmd_arr,2);
454 
456 
457  unsigned char s[255];
458  memset(s, 0, 255);
459  r = pSerial->receiveBytes(s, 7);
460  if (r != 7)
461  {
462  yCError(RPLIDAR, "Received answer with wrong length: %d", r);
463  return false;
464  }
465 
466  if ((unsigned char)s[0] != 0xA5 || (unsigned char)s[1] != 0x5A || (unsigned char)s[2] != 0x05 ||
467  (unsigned char)s[5] != 0x40 || (unsigned char)s[6] != 0x81)
468  {
469  yCError(RPLIDAR, "Invalid answer header");
470  return false;
471  }
472 
473  return true;
474 }
475 
476 bool RpLidar::HW_stop()
477 {
478  pSerial->flush();
479 
480  unsigned char cmd_arr[2];
481  cmd_arr[0] = 0xA5;
482  cmd_arr[1] = 0x25;
483  pSerial->send((char*)cmd_arr,2);
484 
486  return true;
487 }
488 
489 #define DEBUG_LOCKING 1
490 
492 {
493 #ifdef DEBUG_TIMING
494  double t1 = yarp::os::Time::now();
495 #endif
496  const int packet = 100;
497  std::lock_guard<std::mutex> guard(mutex);
498 
499  unsigned char buff[packet*3];
500  memset(buff, 0, packet*3);
501 
502  unsigned int r = 0;
503  static unsigned int total_r = 0;
504  unsigned int count = 0;
505  do
506  {
507  r = pSerial->receiveBytes(buff, packet);
508 #ifdef DEBUG_BYTES_READ_1
509  yCDebug(RPLIDAR) << r;
510 #endif
511  buffer->write_elems(buff, r);
512  count++;
513  total_r += r;
514 #ifdef DEBUG_BYTES_READ_2
515  if (r < packet)
516  {
517  yCDebug(RPLIDAR) << "R" << r;
518  }
519 #endif
520  }
521  while (buffer->size() < (packet * 2) || r < packet);
522 
523  unsigned char minibuff[15];
524  unsigned int ok_count = 0;
525  bool new_scan = false;
526  do
527  {
528  buffer->select_elems(minibuff,15);
529 
530  int start = (minibuff[0]) & 0x01;
531  int lock = (minibuff[0] >> 1) & 0x01;
532  int check = (minibuff[1] & 0x01);
533 
534  int start_n1 = (minibuff[5]) & 0x01;
535  int lock_n1 = (minibuff[5] >> 1) & 0x01;
536  int start_n2 = (minibuff[10]) & 0x01;
537  int lock_n2 = (minibuff[10] >> 1) & 0x01;
538  int check_n1 = (minibuff[6] & 0x01);
539  int check_n2 = (minibuff[11] & 0x01);
540 
541  int quality = (minibuff[0] >> 2);
542  int i_angle = ((minibuff[2] >> 1) << 8) | (minibuff[1]);
543  int i_distance = (minibuff[4] << 8) | (minibuff[3]); //this is ok!
544 
545  if (start == lock)
546  {
547 #ifdef DEBUG_LOCKING
548  yCError(RPLIDAR) << "lock error 1 " << "previous ok" << ok_count << "total r" << total_r;
549 #endif
550  buffer->throw_away_elem();
551  new_scan = false;
552  ok_count = 0;
553  continue;
554  }
555 
556  if (start_n1 == lock_n1)
557  {
558 #ifdef DEBUG_LOCKING
559  yCError(RPLIDAR) << "lock error 2 " << "previous ok" << ok_count << "total r" << total_r;
560 #endif
561  buffer->throw_away_elem();
562  new_scan = false;
563  ok_count = 0;
564  continue;
565  }
566 
567  if (start_n2 == lock_n2)
568  {
569 #ifdef DEBUG_LOCKING
570  yCError(RPLIDAR) << "lock error 3 " << "previous ok" << ok_count << "total r" << total_r;
571 #endif
572  buffer->throw_away_elem();
573  new_scan = false;
574  ok_count = 0;
575  continue;
576  }
577 
578  if (start == 1 && start_n1 == 1)
579  {
580 #ifdef DEBUG_LOCKING
581  yCError(RPLIDAR) << "lock error 4 " << "previous ok" << ok_count << "total r" << total_r;
582 #endif
583  buffer->throw_away_elem();
584  new_scan = false;
585  ok_count = 0;
586  continue;
587  }
588 
589  if (check != 1)
590  {
591 #ifdef DEBUG_LOCKING
592  yCError(RPLIDAR) << "checksum error 1" << "previous ok" << ok_count << "total r" << total_r;
593 #endif
594  buffer->throw_away_elem();
595  new_scan = false;
596  ok_count = 0;
597  continue;
598  }
599 
600  if (check_n1 != 1)
601  {
602 #ifdef DEBUG_LOCKING
603  yCError(RPLIDAR) << "checksum error 2" << "previous ok" << ok_count << "total r" << total_r;
604 #endif
605  buffer->throw_away_elem();
606  new_scan = false;
607  ok_count = 0;
608  continue;
609  }
610 
611  if (check_n2 != 1)
612  {
613 #ifdef DEBUG_LOCKING
614  yCError(RPLIDAR) << "checksum error 3" << "previous ok" << ok_count << "total r" << total_r;
615 #endif
616  buffer->throw_away_elem();
617  new_scan = false;
618  ok_count = 0;
619  continue;
620  }
621 
622 #ifdef DEBUG_LOCKING
623  // yCDebug(RPLIDAR) << "OK" << buffer->get_start() << buffer->get_end() << "total r" << total_r;
624  ok_count++;
625 #endif
626 
627  if (start == 1 && new_scan == false)
628  {
629  //this is a new scan
630  new_scan = true;
631  }
632  else if (start == 1 && new_scan == true)
633  {
634  //end of data
635  new_scan = false;
636  }
637 
638  double distance = i_distance / 4.0 / 1000; //m
639  double angle = i_angle / 64.0; //deg
640  angle = (360 - angle) + 90;
641  if (angle >= 360) angle -= 360;
642 
643  if (i_distance == 0)
644  {
645  // yCWarning(RPLIDAR) << "Invalid Measurement " << i/5;
646  }
647  if (quality == 0)
648  {
649  // yCWarning(RPLIDAR) << "Quality Low" << i / 5;
650  distance = std::numeric_limits<double>::infinity();
651  }
652  if (angle > 360)
653  {
654  yCWarning(RPLIDAR) << "Invalid angle";
655  }
656 
657  if (clip_min_enable)
658  {
659  if (distance < min_distance)
660  distance = max_distance;
661  }
662  if (clip_max_enable)
663  {
664  if (distance > max_distance)
665  {
666  if (!do_not_clip_infinity_enable && distance <= std::numeric_limits<double>::infinity())
667  {
668  distance = max_distance;
669  }
670  }
671  }
672 
673  for (auto& i : range_skip_vector)
674  {
675  if (angle > i.min && angle < i.max)
676  {
677  distance = std::numeric_limits<double>::infinity();
678  }
679  }
680 
681  /*--------------------------------------------------------------*/
682  /* {
683  yCError(RPLIDAR) << "Wrong scan size: " << r;
684  bool b_health = HW_getHealth();
685  if (b_health == true)
686  {
687  if (!HW_reset())
688  {
689  yCError(RPLIDAR, "Unable to reset sensor!");
690  }
691  yCWarning(RPLIDAR, "Sensor reset after error");
692  if (!HW_start())
693  {
694  yCError(RPLIDAR, "Unable to put sensor in scan mode!");
695  }
696  mutex.unlock();
697  return;
698  }
699  else
700  {
701  yCError(RPLIDAR) << "System in error state";
702  }
703  }*/
704  buffer->throw_away_elems(5);
705  //int m_elem = (int)((max_angle - min_angle) / resolution);
706  int elem = (int)(angle / resolution);
707  if (elem >= 0 && elem < (int)laser_data.size())
708  {
709  laser_data[elem] = distance;
710  }
711  else
712  {
713  yCDebug(RPLIDAR) << "RpLidar::run() invalid angle: elem" << elem << ">" << "laser_data.size()" << laser_data.size();
714  }
715  }
716  while (buffer->size() > packet && isRunning() );
717 
718 #ifdef DEBUG_TIMING
719  double t2 = yarp::os::Time::now();
720  yCDebug(RPLIDAR, "Time %f", (t2 - t1) * 1000.0);
721 #endif
722  return;
723 }
724 
726 {
727 #ifdef LASER_DEBUG
728  yCDebug(RPLIDAR, "RpLidar Thread releasing...");
729  yCDebug(RPLIDAR, "... done.");
730 #endif
731 
732  return;
733 }
734 
735 bool RpLidar::getDeviceInfo(std::string &device_info)
736 {
737  std::lock_guard<std::mutex> guard(mutex);
738  device_info = info;
739  return true;
740 }
LogStream.h
yarp::os::Bottle
A simple collection of objects that can be described and transmitted in a portable way.
Definition: Bottle.h:73
RpLidar::getDistanceRange
bool getDistanceRange(double &min, double &max) override
get the device detection range
Definition: rpLidar.cpp:223
yarp::os::Property::put
void put(const std::string &key, const std::string &value)
Associate the given key with the given string.
Definition: Property.cpp:998
yarp::os::Searchable
A base class for nested structures that can be searched.
Definition: Searchable.h:69
yarp::os::Bottle::size
size_type size() const
Gets the number of elements in the bottle.
Definition: Bottle.cpp:254
RpLidar::close
bool close() override
Close the DeviceDriver.
Definition: rpLidar.cpp:206
RpLidar::getRawData
bool getRawData(yarp::sig::Vector &data) override
Get the device measurements.
Definition: rpLidar.cpp:284
yarp::os::Searchable::findGroup
virtual Bottle & findGroup(const std::string &key) const =0
Gets a list corresponding to a given keyword.
yCWarning
#define yCWarning(component,...)
Definition: LogComponent.h:146
RpLidar::getScanLimits
bool getScanLimits(double &min, double &max) override
get the scan angular range.
Definition: rpLidar.cpp:239
DEG2RAD
#define DEG2RAD
Definition: rpLidar.cpp:42
RpLidar::getLaserMeasurement
bool getLaserMeasurement(std::vector< LaserMeasurementData > &data) override
Get the device measurements.
Definition: rpLidar.cpp:292
yarp::os::Searchable::toString
virtual std::string toString() const =0
Return a standard text representation of the content of the object.
rpLidar.h
YARP_LOG_COMPONENT
#define YARP_LOG_COMPONENT(name,...)
Definition: LogComponent.h:80
rpLidarCircularBuffer
Definition: rpLidar.h:46
RpLidar::getScanRate
bool getScanRate(double &rate) override
get the scan rate (scans per seconds)
Definition: rpLidar.cpp:269
RpLidar::getHorizontalResolution
bool getHorizontalResolution(double &step) override
get the angular step between two measurments.
Definition: rpLidar.cpp:255
yarp::dev::IRangefinder2D::Device_status
Device_status
Definition: IRangefinder2D.h:41
RpLidar::getDeviceStatus
bool getDeviceStatus(Device_status &status) override
Definition: rpLidar.cpp:310
RPLIDAR
const yarp::os::LogComponent & RPLIDAR()
Definition: rpLidar.cpp:45
yarp::os::Time::now
double now()
Return the current time in seconds, relative to an arbitrary starting point.
Definition: Time.cpp:124
yarp::dev::Range_t::min
double min
Definition: Lidar2DDeviceBase.h:24
RpLidar::getDeviceInfo
bool getDeviceInfo(std::string &device_info) override
get the device hardware charactestics
Definition: rpLidar.cpp:735
yarp::sig::VectorOf< double >
Log.h
yarp::os::Bottle::get
Value & get(size_type index) const
Reads a Value v from a certain part of the list.
Definition: Bottle.cpp:249
yarp::os::SystemClock::delaySystem
static void delaySystem(double seconds)
Definition: SystemClock.cpp:32
RpLidar::open
bool open(yarp::os::Searchable &config) override
Open the DeviceDriver.
Definition: rpLidar.cpp:62
yarp::dev::Range_t
Definition: Lidar2DDeviceBase.h:23
rpLidarCircularBuffer::~rpLidarCircularBuffer
~rpLidarCircularBuffer()
Definition: rpLidar.cpp:55
yarp::os::Value::asString
virtual std::string asString() const
Get string value.
Definition: Value.cpp:237
yarp::os::Searchable::check
virtual bool check(const std::string &key) const =0
Check if there exists a property of the given name.
buffer
Definition: V4L_camera.h:75
yarp::os::Searchable::find
virtual Value & find(const std::string &key) const =0
Gets a value corresponding to a given keyword.
RpLidar::threadInit
bool threadInit() override
Initialization method.
Definition: rpLidar.cpp:317
RpLidar::setDistanceRange
bool setDistanceRange(double min, double max) override
set the device detection range.
Definition: rpLidar.cpp:231
yCError
#define yCError(component,...)
Definition: LogComponent.h:157
yarp::dev::Range_t::max
double max
Definition: Lidar2DDeviceBase.h:25
yarp::os::Value::asInt32
virtual std::int32_t asInt32() const
Get 32-bit integer value.
Definition: Value.cpp:207
yarp::os::Property::fromConfigFile
bool fromConfigFile(const std::string &fname, bool wipe=true)
Interprets a file as a list of properties.
Definition: Property.cpp:1081
RpLidar::run
void run() override
Loop function.
Definition: rpLidar.cpp:491
yCInfo
#define yCInfo(component,...)
Definition: LogComponent.h:135
yCDebug
#define yCDebug(component,...)
Definition: LogComponent.h:112
RpLidar::setScanRate
bool setScanRate(double rate) override
set the scan rate (scans per seconds)
Definition: rpLidar.cpp:276
yarp::dev::IRangefinder2D::DEVICE_OK_IN_USE
@ DEVICE_OK_IN_USE
Definition: IRangefinder2D.h:43
Time.h
yarp::os::ResourceFinder::findFileByName
std::string findFileByName(const std::string &name)
Find the full path to a file.
Definition: ResourceFinder.cpp:860
yarp::os::Value::asFloat64
virtual yarp::conf::float64_t asFloat64() const
Get 64-bit floating point value.
Definition: Value.cpp:225
RpLidar::setHorizontalResolution
bool setHorizontalResolution(double step) override
get the angular step between two measurments (if available)
Definition: rpLidar.cpp:262
RpLidar::setScanLimits
bool setScanLimits(double min, double max) override
set the scan angular range.
Definition: rpLidar.cpp:247
ResourceFinder.h
yarp::os::Property
A class for storing options and configuration information.
Definition: Property.h:37
yarp::os::ResourceFinder
Helper class for finding config files and other external resources.
Definition: ResourceFinder.h:33
RpLidar::threadRelease
void threadRelease() override
Release method.
Definition: rpLidar.cpp:725