Main MRPT website > C++ reference for MRPT 1.9.9
CVelodyneScanner.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2017, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 #include "hwdrivers-precomp.h" // Precompiled headers
11 
13 #include <mrpt/utils/CStream.h>
14 #include <mrpt/comms/net_utils.h>
16 #include <mrpt/system/filesystem.h>
17 #include <mrpt/utils/bits.h> // for reverseBytesInPlace()
18 
19 #include <thread>
20 
21 // socket's hdrs:
22 #ifdef MRPT_OS_WINDOWS
23 #define _WINSOCK_DEPRECATED_NO_WARNINGS
24 #if defined(_WIN32_WINNT) && (_WIN32_WINNT < 0x600)
25 #undef _WIN32_WINNT
26 #define _WIN32_WINNT 0x600 // Minimum: Windows Vista (required to pollfd)
27 #endif
28 
29 #include <winsock2.h>
30 typedef int socklen_t;
31 
32 #if defined(__BORLANDC__) || defined(_MSC_VER)
33 #pragma comment(lib, "WS2_32.LIB")
34 #endif
35 
36 #else
37 #define INVALID_SOCKET (-1)
38 #include <sys/time.h> // gettimeofday()
39 #include <sys/socket.h>
40 #include <unistd.h>
41 #include <fcntl.h>
42 #include <errno.h>
43 #include <sys/types.h>
44 #include <sys/ioctl.h>
45 #include <netdb.h>
46 #include <arpa/inet.h>
47 #include <netinet/in.h>
48 #include <netinet/tcp.h>
49 #include <poll.h>
50 #endif
51 
52 #if MRPT_HAS_LIBPCAP
53 #include <pcap.h>
54 #if !defined(PCAP_NETMASK_UNKNOWN) // for older pcap versions
55 #define PCAP_NETMASK_UNKNOWN 0xffffffff
56 #endif
57 #endif
58 
59 using namespace mrpt;
60 using namespace mrpt::hwdrivers;
61 using namespace mrpt::obs;
62 using namespace std;
63 
65 
68 
71 {
72  static CVelodyneScanner::model_properties_list_t modelProperties;
73  static bool init = false;
74  if (!init)
75  {
76  init = true;
77  modelProperties[CVelodyneScanner::VLP16].maxRange = 120.0;
78  modelProperties[CVelodyneScanner::HDL32].maxRange = 70.0;
79  modelProperties[CVelodyneScanner::HDL64].maxRange = 120.0;
80  }
81  return modelProperties;
82 }
84 {
87  std::string s;
89  lst.begin();
90  it != lst.end(); ++it)
91  s += mrpt::format(
92  "`%s`,",
94  it->first)
95  .c_str());
96  return s;
97 }
98 
100  : m_model(CVelodyneScanner::VLP16),
101  m_pos_packets_min_period(0.5),
102  m_pos_packets_timing_timeout(30.0),
103  m_device_ip(""),
104  m_pcap_verbose(true),
105  m_last_pos_packet_timestamp(INVALID_TIMESTAMP),
106  m_pcap(nullptr),
107  m_pcap_out(nullptr),
108  m_pcap_dumper(nullptr),
109  m_pcap_bpf_program(nullptr),
110  m_pcap_file_empty(true),
111  m_pcap_read_once(false),
112  m_pcap_read_fast(false),
113  m_pcap_read_full_scan_delay_ms(100),
114  m_pcap_repeat_delay(0.0),
115  m_hDataSock(INVALID_SOCKET),
116  m_hPositionSock(INVALID_SOCKET),
117  m_last_gps_rmc_age(INVALID_TIMESTAMP),
118  m_lidar_rpm(0),
119  m_lidar_return(UNCHANGED)
120 {
121  m_sensorLabel = "Velodyne";
122 
123 #if MRPT_HAS_LIBPCAP
124  m_pcap_bpf_program = new bpf_program[1];
125 #endif
126 
127 #ifdef MRPT_OS_WINDOWS
128  // Init the WinSock Library:
129  WORD wVersionRequested = MAKEWORD(2, 0);
130  WSADATA wsaData;
131  if (WSAStartup(wVersionRequested, &wsaData))
132  THROW_EXCEPTION("Error calling WSAStartup");
133 #endif
134 }
135 
137 {
138  this->close();
139 #ifdef MRPT_OS_WINDOWS
140  WSACleanup();
141 #endif
142 
143 #if MRPT_HAS_LIBPCAP
144  delete[] reinterpret_cast<bpf_program*>(m_pcap_bpf_program);
145  m_pcap_bpf_program = nullptr;
146 #endif
147 }
148 
150  const std::string& velodyne_xml_calib_file_path)
151 {
152  return m_velodyne_calib.loadFromXMLFile(velodyne_xml_calib_file_path);
153 }
154 
156  const mrpt::utils::CConfigFileBase& cfg, const std::string& sect)
157 {
158  MRPT_START
159 
160  cfg.read_enum<CVelodyneScanner::model_t>(sect, "model", m_model);
161  MRPT_LOAD_HERE_CONFIG_VAR(device_ip, string, m_device_ip, cfg, sect);
162  MRPT_LOAD_HERE_CONFIG_VAR(pcap_input, string, m_pcap_input_file, cfg, sect);
164  pcap_output, string, m_pcap_output_file, cfg, sect);
166  pcap_read_once, bool, m_pcap_read_once, cfg, sect);
168  pcap_read_fast, bool, m_pcap_read_fast, cfg, sect);
170  pcap_read_full_scan_delay_ms, double, m_pcap_read_full_scan_delay_ms,
171  cfg, sect);
173  pcap_repeat_delay, double, m_pcap_repeat_delay, cfg, sect);
175  pos_packets_timing_timeout, double, m_pos_packets_timing_timeout, cfg,
176  sect);
178  pos_packets_min_period, double, m_pos_packets_min_period, cfg, sect);
179 
180  using mrpt::utils::DEG2RAD;
182  cfg.read_float(sect, "pose_x", 0), cfg.read_float(sect, "pose_y", 0),
183  cfg.read_float(sect, "pose_z", 0),
184  DEG2RAD(cfg.read_float(sect, "pose_yaw", 0)),
185  DEG2RAD(cfg.read_float(sect, "pose_pitch", 0)),
186  DEG2RAD(cfg.read_float(sect, "pose_roll", 0)));
187 
188  std::string calibration_file;
189  MRPT_LOAD_CONFIG_VAR(calibration_file, string, cfg, sect);
190  if (!calibration_file.empty()) this->loadCalibrationFile(calibration_file);
191 
192  // Check validity:
194  if (lstModels.find(m_model) == lstModels.end())
195  {
197  mrpt::format(
198  "Unrecognized `model` parameter: `%u` . Known values are: %s",
199  static_cast<unsigned int>(m_model),
201  }
202 
203  // Optional HTTP-based settings:
204  MRPT_LOAD_HERE_CONFIG_VAR(rpm, int, m_lidar_rpm, cfg, sect);
206  cfg.read_enum<return_type_t>(sect, "return_type", m_lidar_return);
207 
208  MRPT_END
209 }
210 
214 {
215  try
216  {
217  ASSERTMSG_(m_initialized, "initialize() has not been called yet!");
218 
219  // Init with empty smart pointers:
222 
223  // Try to get data & pos packets:
226  mrpt::system::TTimeStamp data_pkt_timestamp, pos_pkt_timestamp;
227  bool rx_all_ok = this->receivePackets(
228  data_pkt_timestamp, rx_pkt, pos_pkt_timestamp, rx_pos_pkt);
229 
230  if (!rx_all_ok)
231  {
232  // PCAP EOF:
233  return false;
234  }
235 
236  if (pos_pkt_timestamp != INVALID_TIMESTAMP)
237  {
239  mrpt::make_aligned_shared<mrpt::obs::CObservationGPS>();
240  gps_obs->sensorLabel = this->m_sensorLabel + std::string("_GPS");
241  gps_obs->sensorPose = m_sensorPose;
242 
243  gps_obs->originalReceivedTimestamp = pos_pkt_timestamp;
244 
245  bool parsed_ok = CGPSInterface::parse_NMEA(
246  std::string(rx_pos_pkt.NMEA_GPRMC), *gps_obs);
247  const mrpt::obs::gnss::Message_NMEA_RMC* msg_rmc =
248  gps_obs->getMsgByClassPtr<mrpt::obs::gnss::Message_NMEA_RMC>();
249  if (!parsed_ok || !msg_rmc || msg_rmc->fields.validity_char != 'A')
250  {
251  gps_obs->has_satellite_timestamp = false;
252  gps_obs->timestamp = pos_pkt_timestamp;
253  }
254  else
255  {
256  // We have live GPS signal and a recent RMC frame:
257  m_last_gps_rmc_age = pos_pkt_timestamp;
258  m_last_gps_rmc = *msg_rmc;
259  }
260  outGPS = gps_obs; // save in output object
261  }
262 
263  if (data_pkt_timestamp != INVALID_TIMESTAMP)
264  {
265  m_state = ssWorking;
266 
267  // Break into a new observation object when the azimuth passes
268  // 360->0 deg:
269  const uint16_t rx_pkt_start_angle = rx_pkt.blocks[0].rotation;
270  // const uint16_t rx_pkt_end_angle =
271  // rx_pkt.blocks[CObservationVelodyneScan::BLOCKS_PER_PACKET-1].rotation;
272 
273  // Return the observation as done when a complete 360 deg scan is
274  // ready:
275  if (m_rx_scan && !m_rx_scan->scan_packets.empty())
276  {
277  if (rx_pkt_start_angle <
278  m_rx_scan->scan_packets.rbegin()->blocks[0].rotation)
279  {
280  outScan = m_rx_scan;
281  m_rx_scan.reset();
282 
283  if (m_pcap)
284  {
285  // Keep the reader from blowing through the file.
286  if (!m_pcap_read_fast)
287  std::this_thread::sleep_for(
288  std::chrono::duration<double, std::milli>(
290  }
291  }
292  }
293 
294  // Create smart ptr to new in-progress observation:
295  if (!m_rx_scan)
296  {
299  m_rx_scan->sensorLabel =
300  this->m_sensorLabel + std::string("_SCAN");
301  m_rx_scan->sensorPose = m_sensorPose;
302  m_rx_scan->calibration =
303  m_velodyne_calib; // Embed a copy of the calibration info
304 
305  {
306  const model_properties_list_t& lstModels =
309  lstModels.find(this->m_model);
310  if (it != lstModels.end())
311  { // Model params:
312  m_rx_scan->maxRange = it->second.maxRange;
313  }
314  else // default params:
315  {
316  m_rx_scan->maxRange = 120.0;
317  }
318  }
319  }
320 
321  // For the first packet, set timestamp:
322  if (m_rx_scan->scan_packets.empty())
323  {
324  m_rx_scan->originalReceivedTimestamp = data_pkt_timestamp;
325  // Using GPS, if available:
326  if (m_last_gps_rmc.fields.validity_char == 'A' &&
328  m_last_gps_rmc_age, data_pkt_timestamp) <
330  {
331  // Each Velodyne data packet has a timestamp field,
332  // with the number of us since the top of the current HOUR:
333  // take the date and time from the GPS, then modify minutes
334  // and seconds from data pkt:
335  const mrpt::system::TTimeStamp gps_tim =
338 
339  mrpt::system::TTimeParts tim_parts;
340  mrpt::system::timestampToParts(gps_tim, tim_parts);
341  tim_parts.minute =
342  rx_pkt.gps_timestamp /*us from top of hour*/ /
343  60000000ul;
344  tim_parts.second =
345  (rx_pkt.gps_timestamp /*us from top of hour*/ %
346  60000000ul) *
347  1e-6;
348 
349  const mrpt::system::TTimeStamp data_pkt_tim =
351 
352  m_rx_scan->timestamp = data_pkt_tim;
353  m_rx_scan->has_satellite_timestamp = true;
354  }
355  else
356  {
357  m_rx_scan->has_satellite_timestamp = false;
358  m_rx_scan->timestamp = data_pkt_timestamp;
359  }
360  }
361 
362  // Accumulate pkts in the observation object:
363  m_rx_scan->scan_packets.push_back(rx_pkt);
364  }
365 
366  return true;
367  }
368  catch (exception& e)
369  {
370  cerr << "[CVelodyneScanner::getObservation] Returning false due to "
371  "exception: "
372  << endl;
373  cerr << e.what() << endl;
374  return false;
375  }
376 }
377 
379 {
381  CObservationGPS::Ptr obs_gps;
382 
383  if (getNextObservation(obs, obs_gps))
384  {
385  m_state = ssWorking;
386  if (obs) appendObservation(obs);
387  if (obs_gps) appendObservation(obs_gps);
388  }
389  else
390  {
391  m_state = ssError;
392  cerr << "ERROR receiving data from Velodyne devic!" << endl;
393  }
394 }
395 
396 /** Tries to initialize the sensor, after setting all the parameters with a call
397 * to loadConfig.
398 * \exception This method must throw an exception with a descriptive message if
399 * some critical error is found. */
401 {
402  this->close();
403 
404  // (0) Preparation:
405  // --------------------------------
406  // Make sure we have calibration data:
407  if (m_velodyne_calib.empty())
408  {
409  // Try to load default data:
410  m_velodyne_calib = VelodyneCalibration::LoadDefaultCalibration(
412  m_model));
413  if (m_velodyne_calib.empty())
415  "Could not find default calibration data for the given LIDAR "
416  "`model` name. Please, specify a valid `model` or load a valid "
417  "XML configuration file first.");
418  }
419 
420  // online vs off line operation??
421  // -------------------------------
422  if (m_pcap_input_file.empty())
423  { // Online
424 
425  if (m_lidar_rpm > 0)
426  {
427  if (!setLidarRPM(m_lidar_rpm))
428  THROW_EXCEPTION("Error in setLidarRPM()!");
429  }
430  if (m_lidar_return != UNCHANGED)
431  {
433  THROW_EXCEPTION("Error in setLidarReturnType()!");
434  }
435 
436  // (1) Create LIDAR DATA socket
437  // --------------------------------
438  if (INVALID_SOCKET == (m_hDataSock = socket(PF_INET, SOCK_DGRAM, 0)))
440  format(
441  "Error creating UDP socket:\n%s",
443 
444  struct sockaddr_in bindAddr;
445  memset(&bindAddr, 0, sizeof(bindAddr));
446  bindAddr.sin_family = AF_INET;
447  bindAddr.sin_port = htons(VELODYNE_DATA_UDP_PORT);
448  bindAddr.sin_addr.s_addr = INADDR_ANY;
449 
450  if (int(INVALID_SOCKET) ==
451  ::bind(
452  m_hDataSock, (struct sockaddr*)(&bindAddr), sizeof(sockaddr)))
454 
455 #ifdef MRPT_OS_WINDOWS
456  unsigned long non_block_mode = 1;
457  if (ioctlsocket(m_hDataSock, FIONBIO, &non_block_mode))
459  "Error entering non-blocking mode with ioctlsocket().");
460 #else
461  int oldflags = fcntl(m_hDataSock, F_GETFL, 0);
462  if (oldflags == -1)
463  THROW_EXCEPTION("Error retrieving fcntl() of socket.");
464  oldflags |= O_NONBLOCK | FASYNC;
465  if (-1 == fcntl(m_hDataSock, F_SETFL, oldflags))
466  THROW_EXCEPTION("Error entering non-blocking mode with fcntl().");
467 #endif
468 
469  // (2) Create LIDAR POSITION socket
470  // --------------------------------
471  if (INVALID_SOCKET ==
472  (m_hPositionSock = socket(PF_INET, SOCK_DGRAM, 0)))
474  format(
475  "Error creating UDP socket:\n%s",
477 
478  bindAddr.sin_port = htons(VELODYNE_POSITION_UDP_PORT);
479 
480  if (int(INVALID_SOCKET) == ::bind(
482  (struct sockaddr*)(&bindAddr),
483  sizeof(sockaddr)))
485 
486 #ifdef MRPT_OS_WINDOWS
487  if (ioctlsocket(m_hPositionSock, FIONBIO, &non_block_mode))
489  "Error entering non-blocking mode with ioctlsocket().");
490 #else
491  oldflags = fcntl(m_hPositionSock, F_GETFL, 0);
492  if (oldflags == -1)
493  THROW_EXCEPTION("Error retrieving fcntl() of socket.");
494  oldflags |= O_NONBLOCK | FASYNC;
495  if (-1 == fcntl(m_hPositionSock, F_SETFL, oldflags))
496  THROW_EXCEPTION("Error entering non-blocking mode with fcntl().");
497 #endif
498  }
499  else
500  { // Offline:
501 #if MRPT_HAS_LIBPCAP
502  char errbuf[PCAP_ERRBUF_SIZE];
503 
504  if (m_pcap_verbose)
505  printf(
506  "\n[CVelodyneScanner] Opening PCAP file \"%s\"\n",
507  m_pcap_input_file.c_str());
508  if ((m_pcap = pcap_open_offline(m_pcap_input_file.c_str(), errbuf)) ==
509  nullptr)
510  {
511  THROW_EXCEPTION_FMT("Error opening PCAP file: '%s'", errbuf);
512  }
513 
514  // Build PCAP filter:
515  {
516  std::string filter_str = mrpt::format(
517  "(udp dst port %d || udp dst port %d)",
520  if (!m_device_ip.empty())
521  filter_str += "&& src host " + m_device_ip;
522 
523  static std::string sMsgError =
524  "[CVelodyneScanner] Error calling pcap_compile: "; // This is
525  // to avoid
526  // the
527  // ill-formed
528  // signature
529  // of
530  // pcap_error()
531  // accepting
532  // "char*",
533  // not
534  // "const
535  // char*"...
536  // sigh
537  if (pcap_compile(
538  reinterpret_cast<pcap_t*>(m_pcap),
539  reinterpret_cast<bpf_program*>(m_pcap_bpf_program),
540  filter_str.c_str(), 1, PCAP_NETMASK_UNKNOWN) < 0)
541  pcap_perror(reinterpret_cast<pcap_t*>(m_pcap), &sMsgError[0]);
542  }
543 
544  m_pcap_file_empty = true;
545  m_pcap_read_count = 0;
546 
547 #else
549  "Velodyne: Reading from PCAP requires building MRPT with libpcap "
550  "support!");
551 #endif
552  }
553 
557 
558  m_initialized = true;
559 }
560 
562 {
564  {
565  shutdown(m_hDataSock, 2); // SD_BOTH );
566 #ifdef MRPT_OS_WINDOWS
567  closesocket(m_hDataSock);
568 #else
570 #endif
572  }
573 
575  {
576  shutdown(m_hPositionSock, 2); // SD_BOTH );
577 #ifdef MRPT_OS_WINDOWS
578  closesocket(m_hPositionSock);
579 #else
581 #endif
583  }
584 #if MRPT_HAS_LIBPCAP
585  if (m_pcap)
586  {
587  pcap_close(reinterpret_cast<pcap_t*>(m_pcap));
588  m_pcap = nullptr;
589  }
590  if (m_pcap_dumper)
591  {
592  pcap_dump_close(reinterpret_cast<pcap_dumper_t*>(m_pcap_dumper));
593  m_pcap_dumper = nullptr;
594  }
595  if (m_pcap_out)
596  {
597  pcap_close(reinterpret_cast<pcap_t*>(m_pcap_out));
598  m_pcap_out = nullptr;
599  }
600 #endif
601  m_initialized = false;
602 }
603 
604 // Fixed Ethernet headers for PCAP capture --------
605 #if MRPT_HAS_LIBPCAP
606 const uint16_t LidarPacketHeader[21] = {0xffff, 0xffff, 0xffff, 0x7660, 0x0088,
607  0x0000, 0x0008, 0x0045, 0xd204, 0x0000,
608  0x0040, 0x11ff, 0xaab4, 0xa8c0, 0xc801,
609  0xffff, // checksum 0xa9b4 //source ip
610  // 0xa8c0, 0xc801 is
611  // 192.168.1.200
612  0xffff, 0x4009, 0x4009, 0xbe04, 0x0000};
613 const uint16_t PositionPacketHeader[21] = {
614  0xffff, 0xffff, 0xffff, 0x7660, 0x0088, 0x0000, 0x0008, 0x0045, 0xd204,
615  0x0000, 0x0040, 0x11ff, 0xaab4, 0xa8c0, 0xc801, 0xffff, // checksum 0xa9b4
616  // //source ip
617  // 0xa8c0, 0xc801
618  // is 192.168.1.200
619  0xffff, 0x7420, 0x7420, 0x0802, 0x0000};
620 #endif
621 
622 #if defined(MRPT_OS_WINDOWS) && MRPT_HAS_LIBPCAP
623 int gettimeofday(struct timeval* tp, void*)
624 {
625  FILETIME ft;
626  ::GetSystemTimeAsFileTime(&ft);
627  long long t =
628  (static_cast<long long>(ft.dwHighDateTime) << 32) | ft.dwLowDateTime;
629  t -= 116444736000000000LL;
630  t /= 10; // microseconds
631  tp->tv_sec = static_cast<long>(t / 1000000UL);
632  tp->tv_usec = static_cast<long>(t % 1000000UL);
633  return 0;
634 }
635 #endif
636 
638  mrpt::system::TTimeStamp& data_pkt_timestamp,
640  mrpt::system::TTimeStamp& pos_pkt_timestamp,
642 {
645  CObservationVelodyneScan::POS_PACKET_SIZE);
648  CObservationVelodyneScan::PACKET_SIZE);
649 
650  bool ret = true; // all ok
651  if (m_pcap)
652  {
654  data_pkt_timestamp, (uint8_t*)&out_data_pkt, pos_pkt_timestamp,
655  (uint8_t*)&out_pos_pkt);
656  }
657  else
658  {
659  data_pkt_timestamp = internal_receive_UDP_packet(
660  m_hDataSock, (uint8_t*)&out_data_pkt,
661  CObservationVelodyneScan::PACKET_SIZE, m_device_ip);
662  pos_pkt_timestamp = internal_receive_UDP_packet(
663  m_hPositionSock, (uint8_t*)&out_pos_pkt,
664  CObservationVelodyneScan::POS_PACKET_SIZE, m_device_ip);
665  }
666 
667 // Optional PCAP dump:
668 #if MRPT_HAS_LIBPCAP
669  // Save to PCAP file?
670  if (!m_pcap_output_file.empty() &&
671  !m_pcap_out) // 1st time: create output file
672  {
673 #if MRPT_HAS_LIBPCAP
674  char errbuf[PCAP_ERRBUF_SIZE];
675 
678  string sFilePostfix = "_";
679  sFilePostfix += format(
680  "%04u-%02u-%02u_%02uh%02um%02us", (unsigned int)parts.year,
681  (unsigned int)parts.month, (unsigned int)parts.day,
682  (unsigned int)parts.hour, (unsigned int)parts.minute,
683  (unsigned int)parts.second);
684  const string sFileName =
687  string(".pcap");
688 
689  m_pcap_out = pcap_open_dead(DLT_EN10MB, 65535);
690  ASSERTMSG_(
691  m_pcap_out != nullptr, "Error creating PCAP live capture handle");
692 
693  printf(
694  "\n[CVelodyneScanner] Writing to PCAP file \"%s\"\n",
695  sFileName.c_str());
696  if ((m_pcap_dumper = pcap_dump_open(
697  reinterpret_cast<pcap_t*>(m_pcap_out), sFileName.c_str())) ==
698  nullptr)
699  {
701  "Error creating PCAP live dumper: '%s'", errbuf);
702  }
703 #else
705  "Velodyne: Writing PCAP files requires building MRPT with libpcap "
706  "support!");
707 #endif
708  }
709 
710  if (m_pcap_out && m_pcap_dumper &&
711  (data_pkt_timestamp != INVALID_TIMESTAMP ||
712  pos_pkt_timestamp != INVALID_TIMESTAMP))
713  {
714  struct pcap_pkthdr header;
715  struct timeval currentTime;
716  gettimeofday(&currentTime, nullptr);
717  std::vector<unsigned char> packetBuffer;
718 
719  // Data pkt:
720  if (data_pkt_timestamp != INVALID_TIMESTAMP)
721  {
722  header.caplen = header.len =
723  CObservationVelodyneScan::PACKET_SIZE + 42;
724  packetBuffer.resize(header.caplen);
725  header.ts = currentTime;
726 
727  memcpy(&(packetBuffer[0]), LidarPacketHeader, 42);
728  memcpy(
729  &(packetBuffer[0]) + 42, (uint8_t*)&out_data_pkt,
730  CObservationVelodyneScan::PACKET_SIZE);
731  pcap_dump(
732  (u_char*)this->m_pcap_dumper, &header, &(packetBuffer[0]));
733  }
734  // Pos pkt:
735  if (pos_pkt_timestamp != INVALID_TIMESTAMP)
736  {
737  header.caplen = header.len =
738  CObservationVelodyneScan::POS_PACKET_SIZE + 42;
739  packetBuffer.resize(header.caplen);
740  header.ts = currentTime;
741 
742  memcpy(&(packetBuffer[0]), PositionPacketHeader, 42);
743  memcpy(
744  &(packetBuffer[0]) + 42, (uint8_t*)&out_pos_pkt,
745  CObservationVelodyneScan::POS_PACKET_SIZE);
746  pcap_dump(
747  (u_char*)this->m_pcap_dumper, &header, &(packetBuffer[0]));
748  }
749  }
750 #endif
751 
752 // Convert from Velodyne's standard little-endian ordering to host byte
753 // ordering:
754 // (done AFTER saving the pckg as is to pcap above)
755 #if MRPT_IS_BIG_ENDIAN
756  if (data_pkt_timestamp != INVALID_TIMESTAMP)
757  {
759  for (int i = 0; i < CObservationVelodyneScan::BLOCKS_PER_PACKET; i++)
760  {
763  for (int k = 0; k < CObservationVelodyneScan::SCANS_PER_BLOCK; k++)
764  {
766  out_data_pkt.blocks[i].laser_returns[k].distance);
767  }
768  }
769  }
770  if (pos_pkt_timestamp != INVALID_TIMESTAMP)
771  {
774  }
775 #endif
776 
777  // Position packet decimation:
778  if (pos_pkt_timestamp != INVALID_TIMESTAMP)
779  {
782  m_last_pos_packet_timestamp, pos_pkt_timestamp) <
784  {
785  // Ignore this packet
786  pos_pkt_timestamp = INVALID_TIMESTAMP;
787  }
788  else
789  {
790  // Reset time watch:
791  m_last_pos_packet_timestamp = pos_pkt_timestamp;
792  }
793  }
794 
795  return ret;
796 }
797 
798 // static method:
800  platform_socket_t hSocket, uint8_t* out_buffer,
801  const size_t expected_packet_size, const std::string& filter_only_from_IP)
802 {
803  if (hSocket == INVALID_SOCKET)
805  "Error: UDP socket is not open yet! Have you called initialize() "
806  "first?");
807 
808  unsigned long devip_addr = 0;
809  if (!filter_only_from_IP.empty())
810  devip_addr = inet_addr(filter_only_from_IP.c_str());
811 
813 
814  struct pollfd fds[1];
815  fds[0].fd = hSocket;
816  fds[0].events = POLLIN;
817  static const int POLL_TIMEOUT = 1; // (ms)
818 
819  sockaddr_in sender_address;
820  socklen_t sender_address_len = sizeof(sender_address);
821 
822  while (true)
823  {
824  // Unfortunately, the Linux kernel recvfrom() implementation
825  // uses a non-interruptible std::this_thread::sleep_for(ms) when waiting
826  // for data,
827  // which would cause this method to hang if the device is not
828  // providing data. We poll() the device first to make sure
829  // the recvfrom() will not block.
830  //
831  // Note, however, that there is a known Linux kernel bug:
832  //
833  // Under Linux, select() may report a socket file descriptor
834  // as "ready for reading", while nevertheless a subsequent
835  // read blocks. This could for example happen when data has
836  // arrived but upon examination has wrong checksum and is
837  // discarded. There may be other circumstances in which a
838  // file descriptor is spuriously reported as ready. Thus it
839  // may be safer to use O_NONBLOCK on sockets that should not
840  // block.
841 
842  // poll() until input available
843  do
844  {
845  int retval =
846 #if !defined(MRPT_OS_WINDOWS)
847  poll
848 #else
849  WSAPoll
850 #endif
851  (fds, 1, POLL_TIMEOUT);
852  if (retval < 0) // poll() error?
853  {
854  if (errno != EINTR)
856  format(
857  "Error in UDP poll():\n%s",
859  }
860  if (retval == 0) // poll() timeout?
861  {
862  return INVALID_TIMESTAMP;
863  }
864  if ((fds[0].revents & POLLERR) || (fds[0].revents & POLLHUP) ||
865  (fds[0].revents & POLLNVAL)) // device error?
866  {
868  "Error in UDP poll() (seems Velodyne device error?)");
869  }
870  } while ((fds[0].revents & POLLIN) == 0);
871 
872  // Receive packets that should now be available from the
873  // socket using a blocking read.
874  int nbytes = recvfrom(
875  hSocket, (char*)&out_buffer[0], expected_packet_size, 0,
876  (sockaddr*)&sender_address, &sender_address_len);
877 
878  if (nbytes < 0)
879  {
880  if (errno != EWOULDBLOCK) THROW_EXCEPTION("recvfrom() failed!?!")
881  }
882  else if ((size_t)nbytes == expected_packet_size)
883  {
884  // read successful,
885  // if packet is not from the lidar scanner we selected by IP,
886  // continue otherwise we are done
887  if (!filter_only_from_IP.empty() &&
888  sender_address.sin_addr.s_addr != devip_addr)
889  continue;
890  else
891  break; // done
892  }
893 
894  std::cerr
895  << "[CVelodyneScanner] Warning: incomplete Velodyne packet read: "
896  << nbytes << " bytes\n";
897  }
898 
899  // Average the times at which we begin and end reading. Use that to
900  // estimate when the scan occurred.
902 
903  return (time1 / 2 + time2 / 2);
904 }
905 
907  mrpt::system::TTimeStamp& data_pkt_time, uint8_t* out_data_buffer,
908  mrpt::system::TTimeStamp& pos_pkt_time, uint8_t* out_pos_buffer)
909 {
910 #if MRPT_HAS_LIBPCAP
911  ASSERT_(m_pcap);
912 
913  data_pkt_time = INVALID_TIMESTAMP;
914  pos_pkt_time = INVALID_TIMESTAMP;
915 
916  char errbuf[PCAP_ERRBUF_SIZE];
917  struct pcap_pkthdr* header;
918  const u_char* pkt_data;
919 
920  while (true)
921  {
922  int res;
923  if ((res = pcap_next_ex(
924  reinterpret_cast<pcap_t*>(m_pcap), &header, &pkt_data)) >= 0)
925  {
927 
928  // if packet is not from the lidar scanner we selected by IP,
929  // continue
930  if (pcap_offline_filter(
931  reinterpret_cast<bpf_program*>(m_pcap_bpf_program), header,
932  pkt_data) == 0)
933  {
934  if (m_verbose)
935  std::cout
936  << "[CVelodyneScanner] DEBUG: Filtering out packet #"
937  << m_pcap_read_count << " in PCAP file.\n";
938  continue;
939  }
940 
941  // Determine whether it is a DATA or POSITION packet:
942  m_pcap_file_empty = false;
944  const uint16_t udp_dst_port =
945  ntohs(*reinterpret_cast<const uint16_t*>(pkt_data + 0x24));
946 
948  {
949  if (m_verbose)
950  std::cout << "[CVelodyneScanner] DEBUG: Packet #"
952  << " in PCAP file is POSITION pkt.\n";
953  memcpy(
954  out_pos_buffer, pkt_data + 42,
955  CObservationVelodyneScan::POS_PACKET_SIZE);
956  pos_pkt_time = tim; // success
957  return true;
958  }
959  else if (udp_dst_port == CVelodyneScanner::VELODYNE_DATA_UDP_PORT)
960  {
961  if (m_verbose)
962  std::cout << "[CVelodyneScanner] DEBUG: Packet #"
964  << " in PCAP file is DATA pkt.\n";
965  memcpy(
966  out_data_buffer, pkt_data + 42,
967  CObservationVelodyneScan::PACKET_SIZE);
968  data_pkt_time = tim; // success
969  return true;
970  }
971  else
972  {
973  std::cerr << "[CVelodyneScanner] ERROR: Packet "
975  << " in PCAP file passed the filter but does not "
976  "match expected UDP port numbers! Skipping it.\n";
977  }
978  }
979 
980  if (m_pcap_file_empty) // no data in file?
981  {
982  fprintf(
983  stderr,
984  "[CVelodyneScanner] Maybe the PCAP file is empty? Error %d "
985  "reading Velodyne packet: `%s`\n",
986  res, pcap_geterr(reinterpret_cast<pcap_t*>(m_pcap)));
987  return true;
988  }
989 
990  if (m_pcap_read_once)
991  {
992  if (m_pcap_verbose)
993  printf(
994  "[CVelodyneScanner] INFO: end of file reached -- done "
995  "reading.\n");
996  std::this_thread::sleep_for(250ms);
997  return false;
998  }
999 
1000  if (m_pcap_repeat_delay > 0.0)
1001  {
1002  if (m_pcap_verbose)
1003  printf(
1004  "[CVelodyneScanner] INFO: end of file reached -- delaying "
1005  "%.3f seconds.\n",
1007  std::this_thread::sleep_for(
1008  std::chrono::duration<double, std::milli>(
1009  m_pcap_repeat_delay * 1000.0));
1010  }
1011 
1012  if (m_pcap_verbose)
1013  printf("[CVelodyneScanner] INFO: replaying Velodyne dump file.\n");
1014 
1015  // rewind the file
1016  pcap_close(reinterpret_cast<pcap_t*>(m_pcap));
1017  if ((m_pcap = pcap_open_offline(m_pcap_input_file.c_str(), errbuf)) ==
1018  nullptr)
1019  {
1020  THROW_EXCEPTION_FMT("Error opening PCAP file: '%s'", errbuf);
1021  }
1022  m_pcap_file_empty = true; // maybe the file disappeared?
1023  } // loop back and try again
1024 #else
1026  "MRPT needs to be built against libpcap to enable this functionality")
1027 #endif
1028 }
1029 
1031 {
1032  /* HTTP-based config: http://10.0.0.100/tab/config.html
1033  <form name='returns' method="post" action="/cgi/setting">
1034  <span>Return&nbsp;Type:&nbsp;</span> <select name="returns"
1035  onchange='javascript:this.form.submit()'>
1036  <option>Strongest</option>
1037  <option>Last</option>
1038  <option>Dual</option>
1039  </select>
1040  </form>
1041  */
1042  MRPT_START;
1043  std::string strRet;
1044  switch (ret_type)
1045  {
1046  case STRONGEST:
1047  strRet = "Strongest";
1048  break;
1049  case DUAL:
1050  strRet = "Dual";
1051  break;
1052  case LAST:
1053  strRet = "Last";
1054  break;
1055  case UNCHANGED:
1056  return true;
1057  default:
1058  THROW_EXCEPTION("Invalid value for return type!");
1059  };
1060 
1061  const std::string cmd = mrpt::format("returns=%s", strRet.c_str());
1062  return this->internal_send_http_post(cmd);
1063  MRPT_END;
1064 }
1065 
1067 {
1068  /* HTTP-based config: http://10.0.0.100/tab/config.html
1069  <form name='rpm' method="post" action="/cgi/setting">
1070  Motor
1071  &nbsp;RPM:&nbsp;<input type="text" name="rpm" size="5"
1072  style="text-align:right" /><input type="button" value="+"
1073  onclick="javascript:this.form.rpm.value++;this.form.submit()" /><input
1074  type="button" value="-"
1075  onclick="javascript:this.form.rpm.value--;this.form.submit()" />
1076  &nbsp;<input type="submit" value="Set" />
1077  </form>
1078  */
1079 
1080  MRPT_START;
1081  const std::string cmd = mrpt::format("rpm=%i", rpm);
1082  return this->internal_send_http_post(cmd);
1083  MRPT_END;
1084 }
1085 
1087 {
1088  // laser = on|off
1089  MRPT_START;
1090  const std::string cmd = mrpt::format("laser=%s", on ? "on" : "off");
1091  return this->internal_send_http_post(cmd);
1092  MRPT_END;
1093 }
1094 
1096 {
1097  MRPT_START;
1098 
1099  ASSERTMSG_(
1100  !m_device_ip.empty(), "A device IP address must be specified first!");
1101 
1102  using namespace mrpt::comms::net;
1103 
1104  vector_byte post_out;
1105  string post_err_str;
1106 
1107  int http_rep_code;
1108  mrpt::utils::TParameters<string> extra_headers, out_headers;
1109 
1110  extra_headers["Origin"] = mrpt::format("http://%s", m_device_ip.c_str());
1111  extra_headers["Referer"] = mrpt::format("http://%s", m_device_ip.c_str());
1112  extra_headers["Upgrade-Insecure-Requests"] = "1";
1113  extra_headers["Content-Type"] = "application/x-www-form-urlencoded";
1114 
1116  "POST", post_data,
1117  mrpt::format("http://%s/cgi/setting", m_device_ip.c_str()), post_out,
1118  post_err_str, 80 /* port */, string(), string(), // user,pass
1119  &http_rep_code, &extra_headers, &out_headers);
1120 
1121  return mrpt::comms::net::erOk == ret &&
1122  (http_rep_code == 200 || http_rep_code == 204); // OK codes
1123 
1124  MRPT_END;
1125 }
uint64_t TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...
Definition: datetime.h:32
void timestampToParts(TTimeStamp t, TTimeParts &p, bool localTime=false)
Gets the individual parts of a date/time (days, hours, minutes, seconds) - UTC time or local time...
Definition: datetime.cpp:103
double time1
content_t fields
Message content, accesible by individual fields.
std::map< model_t, TModelProperties > model_properties_list_t
bool loadFromXMLFile(const std::string &velodyne_calibration_xml_filename)
Loads calibration from file, in the format supplied by the manufacturer.
A CObservation-derived class for RAW DATA (and optionally, point cloud) of scans from 3D Velodyne LID...
GLdouble GLdouble t
Definition: glext.h:3689
unsigned __int16 uint16_t
Definition: rptypes.h:44
#define MRPT_LOAD_HERE_CONFIG_VAR( variableName, variableType, targetVariable, configFileObject, sectionNameStr)
For usage when passing a dynamic number of (numeric) arguments to a function, by name.
Definition: TParameters.h:57
A C++ interface to Velodyne laser scanners (HDL-64, HDL-32, VLP-16), working on Linux and Windows...
mrpt::system::TTimeStamp getAsTimestamp(const mrpt::system::TTimeStamp &date) const
Build an MRPT timestamp with the hour/minute/sec of this structure and the date from the given timest...
static short int VELODYNE_POSITION_UDP_PORT
Default: 8308.
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
std::vector< uint8_t > vector_byte
Definition: types_simple.h:27
double DEG2RAD(const double x)
Degrees to radians.
int platform_socket_t
Handles for the UDP sockets, or INVALID_SOCKET (-1)
float read_float(const std::string &section, const std::string &name, float defaultValue, bool failIfNotFound=false) const
std::string m_sensorLabel
See CGenericSensor.
bool getNextObservation(mrpt::obs::CObservationVelodyneScan::Ptr &outScan, mrpt::obs::CObservationGPS::Ptr &outGPS)
Polls the UDP port for incoming data packets.
#define THROW_EXCEPTION(msg)
#define THROW_EXCEPTION_FMT(_FORMAT_STRING,...)
bool internal_read_PCAP_packet(mrpt::system::TTimeStamp &data_pkt_time, uint8_t *out_data_buffer, mrpt::system::TTimeStamp &pos_pkt_time, uint8_t *out_pos_buffer)
mrpt::system::TTimeStamp buildTimestampFromParts(const mrpt::system::TTimeParts &p)
Builds a timestamp from the parts (Parts are in UTC)
Definition: datetime.cpp:127
static std::string getListKnownModels()
Return human-readable string: "`VLP16`,`XXX`,...".
std::string getLastSocketErrorStr()
Returns a description of the last Sockets error.
Definition: net_utils.cpp:475
void close()
Close the UDP sockets set-up in initialize().
bool m_pcap_read_once
Default: false.
mrpt::system::TTimeStamp now()
A shortcut for system::getCurrentTime.
Definition: datetime.h:76
Contains classes for various device interfaces.
void * m_pcap_bpf_program
opaque ptr: bpf_program*
STL namespace.
std::string fileNameStripInvalidChars(const std::string &filename, const char replacement_to_invalid_chars='_')
Replace invalid filename chars by underscores (&#39;_&#39;) or any other user-given char. ...
Definition: filesystem.cpp:327
const Scalar * const_iterator
Definition: eigen_plugins.h:27
GLdouble s
Definition: glext.h:3676
int8_t validity_char
This will be: &#39;A&#39;=OK or &#39;V&#39;=void.
bool m_pcap_read_fast
(Default: false) If false, will use m_pcap_read_full_scan_delay_ms
void loadConfig_sensorSpecific(const mrpt::utils::CConfigFileBase &configSource, const std::string &section)
See the class documentation at the top for expected parameters.
UTC_time UTCTime
The GPS sensor measured timestamp (in UTC time)
mrpt::system::TTimeStamp m_last_pos_packet_timestamp
char NMEA_GPRMC[72+234]
the full $GPRMC message, as received by Velodyne, terminated with "\r\n\0"
This class allows loading and storing values and vectors of different types from a configuration text...
unsigned char uint8_t
Definition: rptypes.h:41
double m_pcap_repeat_delay
Default: 0 (in seconds)
mrpt::obs::VelodyneCalibration m_velodyne_calib
Device calibration file (supplied by vendor in an XML file)
ERRORCODE_HTTP
Possible returns from a HTTP request.
Definition: net_utils.h:31
virtual void initialize()
Tries to initialize the sensor driver, after setting all the parameters with a call to loadConfig...
double m_pos_packets_min_period
Default: 0.5 seconds.
#define MRPT_END
std::shared_ptr< CObservationVelodyneScan > Ptr
bool setLidarOnOff(bool on)
Switches the LASER on/off (saves energy when not measuring) (via HTTP post interface).
A helper class that can convert an enum value into its textual representation, and viceversa...
Definition: TEnumType.h:38
nv_oem6_header_t header
Novatel frame: NV_OEM6_BESTPOS.
bool receivePackets(mrpt::system::TTimeStamp &data_pkt_timestamp, mrpt::obs::CObservationVelodyneScan::TVelodyneRawPacket &out_data_pkt, mrpt::system::TTimeStamp &pos_pkt_timestamp, mrpt::obs::CObservationVelodyneScan::TVelodynePositionPacket &out_pos_pkt)
Users normally would prefer calling getNextObservation() instead.
The parts of a date/time (it&#39;s like the standard &#39;tm&#39; but with fractions of seconds).
Definition: datetime.h:38
unsigned int m_pcap_read_count
number of pkts read from the file so far (for debugging)
std::string m_pcap_output_file
Default: "" (do not dump to an offline file)
uint8_t day
Month (1-12)
Definition: datetime.h:42
static const model_properties_list_t & get()
Singleton access.
This namespace contains representation of robot actions and observations.
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
Definition: format.cpp:19
bool m_pcap_verbose
Default: true Output PCAP Info msgs.
#define INVALID_SOCKET
ERRORCODE_HTTP http_request(const string &http_method, const string &http_send_content, const string &url, vector_byte &out_content, string &out_errormsg, int port=80, const string &auth_user=string(), const string &auth_pass=string(), int *out_http_responsecode=nullptr, mrpt::utils::TParameters< string > *extra_headers=nullptr, mrpt::utils::TParameters< string > *out_headers=nullptr, int timeout_ms=1000)
Generic function for HTTP GET & POST methods.
Definition: net_utils.cpp:67
#define DEG2RAD
bool setLidarReturnType(return_type_t ret_type)
Changes among STRONGEST, LAST, DUAL return types (via HTTP post interface).
GLsizei const GLchar ** string
Definition: glext.h:4101
uint16_t header
Block id: UPPER_BANK or LOWER_BANK.
std::string m_pcap_input_file
Default: "" (do not operate from an offline file)
#define IMPLEMENTS_GENERIC_SENSOR(class_name, NameSpace)
This must be inserted in all CGenericSensor classes implementation files:
static bool parse_NMEA(const std::string &cmd_line, mrpt::obs::CObservationGPS &out_obs, const bool verbose=false)
Parses one line of NMEA data from a GPS receiver, and writes the recognized fields (if any) into an o...
ENUMTYPE read_enum(const std::string &section, const std::string &name, const ENUMTYPE &defaultValue, bool failIfNotFound=false) const
Reads an "enum" value, where the value in the config file can be either a numerical value or the symb...
void appendObservation(const mrpt::utils::CSerializable::Ptr &obj)
Like appendObservations() but for just one observation.
#define INVALID_TIMESTAMP
Represents an invalid timestamp, where applicable.
Definition: datetime.h:16
int fprintf(FILE *fil, const char *format,...) noexcept MRPT_printf_format_check(2
An OS-independent version of fprintf.
Definition: os.cpp:405
double time2
double second
Minute (0-59)
Definition: datetime.h:45
#define MRPT_COMPILE_TIME_ASSERT(f)
void * m_pcap_out
opaque ptr: "pcap_t*"
bool internal_send_http_post(const std::string &post_data)
#define MRPT_START
mrpt::system::TTimeStamp getDateAsTimestamp() const
Build an MRPT timestamp with the year/month/day of this observation.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
double m_pos_packets_timing_timeout
Default: 30 seconds.
uint8_t minute
Hour (0-23)
Definition: datetime.h:44
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:88
One unit of data from the scanner (the payload of one UDP DATA packet)
bool empty() const
Returns true if no calibration has been loaded yet.
static short int VELODYNE_DATA_UDP_PORT
Default: 2368.
double m_pcap_read_full_scan_delay_ms
(Default:100 ms) delay after each full scan read from a PCAP log
void * m_pcap
opaque ptr: "pcap_t*"
std::shared_ptr< CObservationGPS > Ptr
uint8_t month
The year.
Definition: datetime.h:41
#define ASSERT_(f)
void doProcess()
This method will be invoked at a minimum rate of "process_rate" (Hz)
A set of useful routines for networking.
Definition: net_utils.h:23
std::shared_ptr< T > make_aligned_shared(Args &&... args)
Creates a shared_ptr with 16-byte aligned memory.
uint8_t hour
Day (1-31)
Definition: datetime.h:43
uint16_t rotation
0-35999, divide by 100 to get degrees
double timeDifference(const mrpt::system::TTimeStamp t_first, const mrpt::system::TTimeStamp t_later)
Returns the time difference from t1 to t2 (positive if t2 is posterior to t1), in seconds...
Definition: datetime.cpp:208
GLuint res
Definition: glext.h:7268
void * m_pcap_dumper
opaque ptr: "pcap_dumper_t *"
#define MRPT_LOAD_CONFIG_VAR( variableName, variableType, configFileObject, sectionNameStr)
An useful macro for loading variables stored in a INI-like file under a key with the same name that t...
void reverseBytesInPlace(bool &v_in_out)
Reverse the order of the bytes of a given type (useful for transforming btw little/big endian) ...
std::string m_device_ip
Default: "" (no IP-based filtering)
bool loadCalibrationFile(const std::string &velodyne_xml_calib_file_path)
Returns false on error.
#define ASSERTMSG_(f, __ERROR_MSG)
mrpt::system::TTimeStamp m_last_gps_rmc_age
mrpt::obs::CObservationVelodyneScan::Ptr m_rx_scan
In progress RX scan.
static mrpt::system::TTimeStamp internal_receive_UDP_packet(platform_socket_t hSocket, uint8_t *out_buffer, const size_t expected_packet_size, const std::string &filter_only_from_IP)
model_t m_model
Default: "VLP16".
mrpt::obs::gnss::Message_NMEA_RMC m_last_gps_rmc
void memcpy(void *dest, size_t destSize, const void *src, size_t copyCount) noexcept
An OS and compiler independent version of "memcpy".
Definition: os.cpp:355
bool setLidarRPM(int rpm)
Changes Lidar RPM (valid range: 300-600) (via HTTP post interface).



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019