Go to the documentation of this file.
10 #include <gtest/gtest.h>
22 TEST(COctoMapTests, updateVoxels)
51 TEST(COctoMapTests, insert2DScan)
TPoint3D_< double > TPoint3D
Lightweight 3D point.
EXPECT_TRUE(mrpt::system::fileExists(ini_fil))
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
bool insertObservation(const mrpt::obs::CObservation &obs, const mrpt::poses::CPose3D *robotPose=nullptr)
Insert the observation information into this map.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
This namespace contains representation of robot actions and observations.
TEST(COctoMapTests, updateVoxels)
bool getPointOccupancy(const float x, const float y, const float z, double &prob_occupancy) const
Get the occupancy probability [0,1] of a point.
EXPECT_LT(out.final_rmse, 3.0)
A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ ...
void example2DRangeScan(mrpt::obs::CObservation2DRangeScan &s, int i=0)
Example 2D lidar scans (form a venerable SICK LMS200).
This base provides a set of functions for maths stuff.
void updateVoxel(const double x, const double y, const double z, bool occupied)
Manually updates the occupancy of the voxel at (x,y,z) as being occupied (true) or free (false),...
EXPECT_GT(out.final_iters, 10UL)
Page generated by Doxygen 1.8.17 for MRPT 2.0.4 at Fri Jul 17 08:43:33 UTC 2020 | |