10 #include <gtest/gtest.h> 13 #include <test_mrpt_common.h> 19 #include <mrpt/config.h> 25 UNITTEST_BASEDIR + string(
"/tests/sample_velodyne_vlp16_gps.pcap");
29 std::cerr <<
"WARNING: Skipping test due to missing file: " << fil
44 size_t nScans = 0, nGPS = 0;
46 for (
size_t i = 0; i < 1000 && rx_ok; i++)
54 scan->generatePointCloud();
65 UNITTEST_BASEDIR + string(
"/tests/sample_velodyne_hdl32.pcap");
69 std::cerr <<
"WARNING: Skipping test due to missing file: " << fil
87 for (
size_t i = 0; i < 1000 && rx_ok; i++)
98 #endif // MRPT_HAS_LIBPCAP
A C++ interface to Velodyne laser scanners (HDL-64, HDL-32, VLP-16), working on Linux and Windows...
EXPECT_GT(out.final_iters, 10UL)
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.
TEST(ICP_SLAM_App, MapFromRawlog_PointMap)
void initialize() override
Tries to initialize the sensor driver, after setting all the parameters with a call to loadConfig...
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
EXPECT_EQ(out.image_pair_was_used.size(), NUM_IMGS)
void setPCAPInputFileReadOnce(bool read_once)