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-2018, 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 std;
17 
18 // Defined in tests/test_main.cpp
19 namespace mrpt
20 {
22 }
23 
24 #include <mrpt/config.h>
25 #if MRPT_HAS_LIBPCAP
26 
27 TEST(CVelodyneScanner, sample_vlp16_dataset)
28 {
29  const string fil = MRPT_GLOBAL_UNITTEST_SRC_DIR +
30  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
35  << "\n";
36  return;
37  }
38 
39  CVelodyneScanner velodyne;
40 
42  velodyne.setPCAPInputFile(fil);
43  velodyne.setPCAPInputFileReadOnce(true);
44  velodyne.enableVerbose(false);
45  velodyne.setPCAPVerbosity(false);
46 
47  velodyne.initialize();
48 
49  size_t nScans = 0, nGPS = 0;
50  bool rx_ok = true;
51  for (size_t i = 0; i < 1000 && rx_ok; i++)
52  {
55  rx_ok = velodyne.getNextObservation(scan, gps);
56  if (scan)
57  {
58  nScans++;
59  scan->generatePointCloud();
60  }
61  if (gps) nGPS++;
62  };
63  EXPECT_EQ(nScans, 4U);
64  EXPECT_GT(nGPS, 0U);
65 }
66 
67 TEST(CVelodyneScanner, sample_hdl32_dataset)
68 {
69  const string fil = MRPT_GLOBAL_UNITTEST_SRC_DIR +
70  string("/tests/sample_velodyne_hdl32.pcap");
71 
72  if (!mrpt::system::fileExists(fil))
73  {
74  std::cerr << "WARNING: Skipping test due to missing file: " << fil
75  << "\n";
76  return;
77  }
78 
79  CVelodyneScanner velodyne;
80 
82  velodyne.setPCAPInputFile(fil);
83  velodyne.setPCAPInputFileReadOnce(true);
84  velodyne.enableVerbose(false);
85  velodyne.setPCAPVerbosity(false);
86 
87  velodyne.initialize();
88 
89  size_t nScans = 0;
90  // size_t nGPS=0;
91  bool rx_ok = true;
92  for (size_t i = 0; i < 1000 && rx_ok; i++)
93  {
96  rx_ok = velodyne.getNextObservation(scan, gps);
97  if (scan) nScans++;
98  // if (gps) nGPS++;
99  };
100  EXPECT_EQ(nScans, 3U);
101 }
102 
103 #endif // MRPT_HAS_LIBPCAP
filesystem.h
mrpt::hwdrivers::CVelodyneScanner::setPCAPInputFile
void setPCAPInputFile(const std::string &pcap_file)
Enables reading from a PCAP file instead of live UDP packet listening.
Definition: CVelodyneScanner.h:296
mrpt::hwdrivers::CVelodyneScanner::getNextObservation
bool getNextObservation(mrpt::obs::CObservationVelodyneScan::Ptr &outScan, mrpt::obs::CObservationGPS::Ptr &outGPS)
Polls the UDP port for incoming data packets.
Definition: CVelodyneScanner.cpp:211
mrpt::hwdrivers::CVelodyneScanner::VLP16
@ VLP16
Definition: CVelodyneScanner.h:180
mrpt::hwdrivers
Contains classes for various device interfaces.
Definition: C2DRangeFinderAbstract.h:22
mrpt::hwdrivers::CGenericSensor::enableVerbose
void enableVerbose(bool enabled=true)
Enable or disable extra debug info dumped to std::cout during sensor operation.
Definition: CGenericSensor.h:105
mrpt::hwdrivers::CVelodyneScanner::setPCAPVerbosity
void setPCAPVerbosity(const bool verbose)
Enables/disables PCAP info messages to console (default: true)
Definition: CVelodyneScanner.h:294
mrpt
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
Definition: CKalmanFilterCapable.h:30
mrpt::hwdrivers::CVelodyneScanner::setModelName
void setModelName(const model_t model)
See supported model names in the general discussion docs for mrpt::hwdrivers::CVelodyneScanner.
Definition: CVelodyneScanner.h:267
mrpt::hwdrivers::CVelodyneScanner::HDL32
@ HDL32
Definition: CVelodyneScanner.h:181
mrpt::system::fileExists
bool fileExists(const std::string &fileName)
Test if a given file (or directory) exists.
Definition: filesystem.cpp:127
CVelodyneScanner.h
mrpt::hwdrivers::CVelodyneScanner::initialize
virtual void initialize()
Tries to initialize the sensor driver, after setting all the parameters with a call to loadConfig.
Definition: CVelodyneScanner.cpp:401
mrpt::hwdrivers::CVelodyneScanner
A C++ interface to Velodyne laser scanners (HDL-64, HDL-32, VLP-16), working on Linux and Windows.
Definition: CVelodyneScanner.h:168
mrpt::obs::CObservationVelodyneScan::Ptr
std::shared_ptr< CObservationVelodyneScan > Ptr
Definition: CObservationVelodyneScan.h:77
mrpt::obs::CObservationGPS::Ptr
std::shared_ptr< CObservationGPS > Ptr
Definition: CObservationGPS.h:72
mrpt::MRPT_GLOBAL_UNITTEST_SRC_DIR
std::string MRPT_GLOBAL_UNITTEST_SRC_DIR
Definition: CLogFileRecord_unittest.cpp:25
TEST
TEST(SocketTests, send_receive_object)
Definition: sockets_unittest.cpp:16
string
GLsizei const GLchar ** string
Definition: glext.h:4101
mrpt::hwdrivers::CVelodyneScanner::setPCAPInputFileReadOnce
void setPCAPInputFileReadOnce(bool read_once)
Definition: CVelodyneScanner.h:308



Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at miƩ 12 jul 2023 10:03:34 CEST