Main MRPT website > C++ reference for MRPT 1.9.9
CVelodyneScanner_unittest.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 
11 #include <mrpt/system/filesystem.h>
12 #include <gtest/gtest.h>
13 
14 using namespace mrpt;
15 using namespace mrpt::hwdrivers;
16 using namespace mrpt::utils;
17 using namespace std;
18 
19 // Defined in tests/test_main.cpp
20 namespace mrpt
21 {
22 namespace utils
23 {
25 }
26 }
27 
28 #include <mrpt/config.h>
29 #if MRPT_HAS_LIBPCAP
30 
31 TEST(CVelodyneScanner, sample_vlp16_dataset)
32 {
33  const string fil = MRPT_GLOBAL_UNITTEST_SRC_DIR +
34  string("/tests/sample_velodyne_vlp16_gps.pcap");
35 
36  if (!mrpt::system::fileExists(fil))
37  {
38  std::cerr << "WARNING: Skipping test due to missing file: " << fil
39  << "\n";
40  return;
41  }
42 
43  CVelodyneScanner velodyne;
44 
46  velodyne.setPCAPInputFile(fil);
47  velodyne.setPCAPInputFileReadOnce(true);
48  velodyne.enableVerbose(false);
49  velodyne.setPCAPVerbosity(false);
50 
51  velodyne.initialize();
52 
53  size_t nScans = 0, nGPS = 0;
54  bool rx_ok = true;
55  for (size_t i = 0; i < 1000 && rx_ok; i++)
56  {
59  rx_ok = velodyne.getNextObservation(scan, gps);
60  if (scan)
61  {
62  nScans++;
63  scan->generatePointCloud();
64  }
65  if (gps) nGPS++;
66  };
67  EXPECT_EQ(nScans, 4U);
68  EXPECT_GT(nGPS, 0U);
69 }
70 
71 TEST(CVelodyneScanner, sample_hdl32_dataset)
72 {
73  const string fil = MRPT_GLOBAL_UNITTEST_SRC_DIR +
74  string("/tests/sample_velodyne_hdl32.pcap");
75 
76  if (!mrpt::system::fileExists(fil))
77  {
78  std::cerr << "WARNING: Skipping test due to missing file: " << fil
79  << "\n";
80  return;
81  }
82 
83  CVelodyneScanner velodyne;
84 
86  velodyne.setPCAPInputFile(fil);
87  velodyne.setPCAPInputFileReadOnce(true);
88  velodyne.enableVerbose(false);
89  velodyne.setPCAPVerbosity(false);
90 
91  velodyne.initialize();
92 
93  size_t nScans = 0;
94  // size_t nGPS=0;
95  bool rx_ok = true;
96  for (size_t i = 0; i < 1000 && rx_ok; i++)
97  {
100  rx_ok = velodyne.getNextObservation(scan, gps);
101  if (scan) nScans++;
102  // if (gps) nGPS++;
103  };
104  EXPECT_EQ(nScans, 3U);
105 }
106 
107 #endif // MRPT_HAS_LIBPCAP
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
std::string MRPT_GLOBAL_UNITTEST_SRC_DIR
A C++ interface to Velodyne laser scanners (HDL-64, HDL-32, VLP-16), working on Linux and Windows...
void setPCAPInputFile(const std::string &pcap_file)
Enables reading from a PCAP file instead of live UDP packet listening.
void setPCAPVerbosity(const bool verbose)
Enables/disables PCAP info messages to console (default: true)
bool getNextObservation(mrpt::obs::CObservationVelodyneScan::Ptr &outScan, mrpt::obs::CObservationGPS::Ptr &outGPS)
Polls the UDP port for incoming data packets.
void enableVerbose(bool enabled=true)
Enable or disable extra debug info dumped to std::cout during sensor operation.
bool fileExists(const std::string &fileName)
Test if a given file (or directory) exists.
Definition: filesystem.cpp:127
Contains classes for various device interfaces.
STL namespace.
void setModelName(const model_t model)
See supported model names in the general discussion docs for mrpt::hwdrivers::CVelodyneScanner.
virtual void initialize()
Tries to initialize the sensor driver, after setting all the parameters with a call to loadConfig...
std::shared_ptr< CObservationVelodyneScan > Ptr
TEST(Compress, DataBlockGZ)
GLsizei const GLchar ** string
Definition: glext.h:4101
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
std::shared_ptr< CObservationGPS > Ptr
void setPCAPInputFileReadOnce(bool read_once)



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