Go to the documentation of this file.
10 #include <gtest/gtest.h>
18 #include <test_mrpt_common.h>
20 TEST(CObservationRotatingScan, fromKittiUndistorted)
22 using namespace std::string_literals;
23 const auto fil = mrpt::UNITTEST_BASEDIR +
"/tests/kitti_00_000000.bin.gz"s;
26 bool read_ok = pts->loadFromKittiVelodyneFile(fil);
32 pts->saveToKittiVelodyneFile(
"/tmp/a.bin.gz");
33 pts->saveXYZI_to_text_file(
"/tmp/a.txt");
42 TEST(CObservationRotatingScan, fromVelodyne)
44 using namespace std::string_literals;
46 "/datasets/test_velodyne_VLP16.rawlog"s;
66 TEST(CObservationRotatingScan, from2DScan)
68 using namespace std::string_literals;
This class stores a rawlog (robotic datasets) in one of two possible formats:
EXPECT_TRUE(mrpt::system::fileExists(ini_fil))
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
std::string getShareMRPTDir()
Attempts to find the directory [PREFIX/]share/mrpt/ and returns its absolute path,...
uint16_t rowCount
Number of "Lidar rings" (e.g.
static Ptr Create(Args &&... args)
EXPECT_NEAR(out.cam_params.rightCameraPose.x, 0.1194, 0.005)
void fromVelodyne(const mrpt::obs::CObservationVelodyneScan &o)
CSensoryFrame::Ptr getAsObservations(size_t index) const
Returns the i'th element in the sequence, as being an action, where index=0 is the first object.
bool loadFromRawLogFile(const std::string &fileName, bool non_obs_objects_are_legal=false)
Load the contents from a file containing one of these possibilities:
A CObservation-derived class for raw range data from a 2D or 3D rotating scanner.
void fromScan2D(const mrpt::obs::CObservation2DRangeScan &o)
TEST(CObservationRotatingScan, fromKittiUndistorted)
EXPECT_EQ(out.image_pair_was_used.size(), NUM_IMGS)
T::ConstPtr asObservation(size_t index) const
Get the i'th observation as an observation of the given type.
An observation from any sensor that can be summarized as a pointcloud.
uint16_t columnCount
Number of lidar "firings" for this scan.
A CObservation-derived class for RAW DATA (and optionally, point cloud) of scans from 3D Velodyne LID...
Page generated by Doxygen 1.8.17 for MRPT 2.0.4 at Fri Jul 17 08:43:33 UTC 2020 | |