12 #include <gtest/gtest.h> 28 #include <mrpt/config.h> 34 string(
"/tests/sample_velodyne_vlp16_gps.pcap");
38 std::cerr <<
"WARNING: Skipping test due to missing file: " << fil
53 size_t nScans = 0, nGPS = 0;
55 for (
size_t i = 0; i < 1000 && rx_ok; i++)
63 scan->generatePointCloud();
67 EXPECT_EQ(nScans, 4U);
74 string(
"/tests/sample_velodyne_hdl32.pcap");
78 std::cerr <<
"WARNING: Skipping test due to missing file: " << fil
96 for (
size_t i = 0; i < 1000 && rx_ok; i++)
104 EXPECT_EQ(nScans, 3U);
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.
Contains classes for various device interfaces.
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
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
std::shared_ptr< CObservationGPS > Ptr
void setPCAPInputFileReadOnce(bool read_once)