Main MRPT website > C++ reference for MRPT 1.5.5
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 { namespace utils {
22  }
23 }
24 
25 #include <mrpt/config.h>
26 #if MRPT_HAS_LIBPCAP
27 
28 TEST(CVelodyneScanner, sample_vlp16_dataset)
29 {
30  const string fil = MRPT_GLOBAL_UNITTEST_SRC_DIR + string("/tests/sample_velodyne_vlp16_gps.pcap");
31 
32  if (!mrpt::system::fileExists(fil))
33  {
34  std::cerr << "WARNING: Skipping test due to missing file: " << fil << "\n";
35  return;
36  }
37 
38  CVelodyneScanner velodyne;
39 
41  velodyne.setPCAPInputFile(fil);
42  velodyne.setPCAPInputFileReadOnce(true);
43  velodyne.enableVerbose(false);
44  velodyne.setPCAPVerbosity(false);
45 
46  velodyne.initialize();
47 
48  size_t nScans = 0, nGPS=0;
49  bool rx_ok = true;
50  for (size_t i=0;i<1000 && rx_ok;i++)
51  {
52  mrpt::obs::CObservationVelodyneScanPtr scan;
53  mrpt::obs::CObservationGPSPtr gps;
54  rx_ok = velodyne.getNextObservation(scan,gps);
55  if (scan) { nScans++;
56  scan->generatePointCloud();
57  }
58  if (gps) nGPS++;
59  };
60  EXPECT_EQ(nScans,4U);
61  EXPECT_GT(nGPS,0U);
62 }
63 
64 TEST(CVelodyneScanner, sample_hdl32_dataset)
65 {
66  const string fil = MRPT_GLOBAL_UNITTEST_SRC_DIR + string("/tests/sample_velodyne_hdl32.pcap");
67 
68  if (!mrpt::system::fileExists(fil))
69  {
70  std::cerr << "WARNING: Skipping test due to missing file: " << fil << "\n";
71  return;
72  }
73 
74  CVelodyneScanner velodyne;
75 
77  velodyne.setPCAPInputFile(fil);
78  velodyne.setPCAPInputFileReadOnce(true);
79  velodyne.enableVerbose(false);
80  velodyne.setPCAPVerbosity(false);
81 
82  velodyne.initialize();
83 
84  size_t nScans = 0;
85 // size_t nGPS=0;
86  bool rx_ok = true;
87  for (size_t i=0;i<1000 && rx_ok;i++)
88  {
89  mrpt::obs::CObservationVelodyneScanPtr scan;
90  mrpt::obs::CObservationGPSPtr gps;
91  rx_ok = velodyne.getNextObservation(scan,gps);
92  if (scan) nScans++;
93 // if (gps) nGPS++;
94  };
95  EXPECT_EQ(nScans,3U);
96 }
97 
98 #endif // MRPT_HAS_LIBPCAP
99 
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
Definition: zip.h:16
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)
void enableVerbose(bool enabled=true)
Enable or disable extra debug info dumped to std::cout during sensor operation.
bool BASE_IMPEXP fileExists(const std::string &fileName)
Test if a given file (or directory) exists.
Definition: filesystem.cpp:124
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...
TEST(Compress, DataBlockGZ)
GLsizei const GLchar ** string
Definition: glext.h:3919
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
bool getNextObservation(mrpt::obs::CObservationVelodyneScanPtr &outScan, mrpt::obs::CObservationGPSPtr &outGPS)
Polls the UDP port for incoming data packets.
void setPCAPInputFileReadOnce(bool read_once)



Page generated by Doxygen 1.8.14 for MRPT 1.5.5 Git: e06b63dbf Fri Dec 1 14:41:11 2017 +0100 at lun oct 28 01:31:35 CET 2019