20 template <
class OCTREE,
class OCTREE_NODE>
26 template <
class OCTREE,
class OCTREE_NODE>
28 : insertionOptions(*this),
29 m_impl(new Impl({resolution}))
32 template <
class OCTREE,
class OCTREE_NODE>
33 template <
class octomap_po
int3d,
class octomap_po
intcloud>
34 bool COctoMapBase<OCTREE, OCTREE_NODE>::
35 internal_build_PointCloud_for_observation(
38 octomap_pointcloud& scan)
const 47 robotPose3D = (*robotPose);
64 octomap::point3d(sensorPose.
x(), sensorPose.
y(), sensorPose.z());
68 const size_t nPts = scanPts->
size();
74 for (
size_t i = 0; i < nPts; i++)
77 scanPts->getPointFast(i, pt.
x, pt.
y, pt.
z);
84 scan.push_back(gx, gy, gz);
104 octomap::point3d(sensorPose.
x(), sensorPose.
y(), sensorPose.z());
108 const size_t sizeRangeScan = o->
points3D_x.size();
111 scan.reserve(sizeRangeScan);
116 const float m00 = H.get_unsafe(0, 0);
117 const float m01 = H.get_unsafe(0, 1);
118 const float m02 = H.get_unsafe(0, 2);
119 const float m03 = H.get_unsafe(0, 3);
120 const float m10 = H.get_unsafe(1, 0);
121 const float m11 = H.get_unsafe(1, 1);
122 const float m12 = H.get_unsafe(1, 2);
123 const float m13 = H.get_unsafe(1, 3);
124 const float m20 = H.get_unsafe(2, 0);
125 const float m21 = H.get_unsafe(2, 1);
126 const float m22 = H.get_unsafe(2, 2);
127 const float m23 = H.get_unsafe(2, 3);
130 for (
size_t i = 0; i < sizeRangeScan; i++)
137 if (pt.
x != 0 || pt.
y != 0 || pt.
z != 0)
140 const float gx = m00 * pt.
x + m01 * pt.
y + m02 * pt.
z + m03;
141 const float gy = m10 * pt.
x + m11 * pt.
y + m12 * pt.
z + m13;
142 const float gz = m20 * pt.
x + m21 * pt.
y + m22 * pt.
z + m23;
145 scan.push_back(gx, gy, gz);
154 template <
class OCTREE,
class OCTREE_NODE>
164 mrpt::make_aligned_shared<mrpt::opengl::CSetOfObjects>();
166 this->getAs3DObject(obj3D);
177 m_impl->m_octomap.writeBinaryConst(fil);
182 template <
class OCTREE,
class OCTREE_NODE>
186 octomap::point3d sensorPt;
187 octomap::Pointcloud scan;
189 if (!internal_build_PointCloud_for_observation(
190 obs, &takenFrom, sensorPt, scan))
193 octomap::OcTreeKey key;
194 const size_t N = scan.size();
197 for (
size_t i = 0; i < N; i += likelihoodOptions.decimation)
199 if (m_impl->m_octomap
200 .coordToKeyChecked(scan.getPoint(i), key))
203 m_impl->m_octomap.search(key, 0 );
204 if (node) log_lik += std::log(node->getOccupancy());
211 template <
class OCTREE,
class OCTREE_NODE>
213 const float x,
const float y,
const float z,
double& prob_occupancy)
const 215 octomap::OcTreeKey key;
216 if (m_impl->m_octomap
217 .coordToKeyChecked(octomap::point3d(
x,
y,
z), key))
220 m_impl->m_octomap.search(key, 0 );
221 if (!node)
return false;
223 prob_occupancy = node->getOccupancy();
230 template <
class OCTREE,
class OCTREE_NODE>
232 const CPointsMap& ptMap,
const float sensor_x,
const float sensor_y,
233 const float sensor_z)
236 const octomap::point3d sensorPt(sensor_x, sensor_y, sensor_z);
238 const float *xs, *ys, *zs;
240 for (
size_t i = 0; i < N; i++)
243 sensorPt, octomap::point3d(xs[i], ys[i], zs[i]),
244 insertionOptions.maxrange, insertionOptions.pruning);
248 template <
class OCTREE,
class OCTREE_NODE>
253 octomap::point3d _end;
258 octomap::point3d(origin.
x, origin.
y, origin.
z),
259 octomap::point3d(direction.
x, direction.
y, direction.
z), _end,
260 ignoreUnknownCells, maxRange);
271 template <
class OCTREE,
class OCTREE_NODE>
281 clampingThresMin(0.1192),
282 clampingThresMax(0.971)
286 template <
class OCTREE,
class OCTREE_NODE>
295 clampingThresMin(0.1192),
296 clampingThresMax(0.971)
300 template <
class OCTREE,
class OCTREE_NODE>
306 template <
class OCTREE,
class OCTREE_NODE>
315 template <
class OCTREE,
class OCTREE_NODE>
333 template <
class OCTREE,
class OCTREE_NODE>
335 std::ostream& out)
const 338 "\n----------- [COctoMapBase<>::TInsertionOptions] ------------ \n\n");
352 template <
class OCTREE,
class OCTREE_NODE>
354 std::ostream& out)
const 357 "\n----------- [COctoMapBase<>::TLikelihoodOptions] ------------ \n\n");
365 template <
class OCTREE,
class OCTREE_NODE>
386 template <
class OCTREE,
class OCTREE_NODE>
394 template <
class OCTREE,
class OCTREE_NODE>
400 out << generateGridLines << generateOccupiedVoxels << visibleOccupiedVoxels
401 << generateFreeVoxels << visibleFreeVoxels;
404 template <
class OCTREE,
class OCTREE_NODE>
414 in >> generateGridLines >> generateOccupiedVoxels >>
415 visibleOccupiedVoxels >> generateFreeVoxels >>
double x() const
Common members of all points & poses classes.
virtual void setProbMiss(double prob)=0
virtual double getOccupancyThres() const =0
virtual double getClampingThresMin() const =0
const POINTSMAP * buildAuxPointsMap(const void *options=nullptr) const
Returns a cached points map representing this laser scan, building it upon the first call...
Declares a class derived from "CObservation" that encapsules a 3D range scan measurement, as from a time-of-flight range camera or any other RGBD sensor.
virtual void setProbHit(double prob)=0
virtual double getClampingThresMax() const =0
void readFromStream(mrpt::serialization::CArchive &in)
Binary dump to stream.
void writeToStream(mrpt::serialization::CArchive &out) const
Binary dump to stream.
std::vector< float > points3D_z
#define MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(__V)
For use in CSerializable implementations.
A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ ...
virtual void setClampingThresMin(double thresProb)=0
TLikelihoodOptions()
Initilization of default parameters.
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans or other sensors...
A numeric matrix of compile-time fixed size.
This class allows loading and storing values and vectors of different types from a configuration text...
std::vector< float > points3D_y
Lightweight 3D point (float version).
void composeFrom(const CPose3D &A, const CPose3D &B)
Makes "this = A (+) B"; this method is slightly more efficient than "this= A + B;" since it avoids th...
void writeToStream(mrpt::serialization::CArchive &out) const
Binary dump to stream.
This namespace contains representation of robot actions and observations.
string iniFile(myDataDir+string("benchmark-options.ini"))
void readFromStream(mrpt::serialization::CArchive &in)
Binary dump to stream.
COctoMapBase(double resolution)
Constructor, defines the resolution of the octomap (length of each voxel side)
double x
X,Y,Z coordinates.
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream.
bool hasPoints3D
true means the field points3D contains valid data.
GLsizei const GLchar ** string
bool castRay(const mrpt::math::TPoint3D &origin, const mrpt::math::TPoint3D &direction, mrpt::math::TPoint3D &end, bool ignoreUnknownCells=false, double maxRange=-1.0) const
Performs raycasting in 3d, similar to computeRay().
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
bool saveToFile(const std::string &fil) const
Saves the scene to a 3Dscene file, loadable by the application SceneViewer3D.
#define LOADABLEOPTS_DUMP_VAR(variableName, variableType)
Macro for dumping a variable to a stream, within the method "dumpToTextStream(out)" (Variable types a...
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string §ion) override
This method load the options from a ".ini"-like file or memory-stored string list.
#define MRPT_LOAD_CONFIG_VAR( variableName, variableType, configFileObject, sectionNameStr)
An useful macro for loading variables stored in a INI-like file under a key with the same name that t...
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
Virtual base class for "archives": classes abstracting I/O streams.
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot.
void getPointsBuffer(size_t &outPointsCount, const float *&xs, const float *&ys, const float *&zs) const
Provides a direct access to points buffer, or nullptr if there is no points in the map...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Declares a class that represents any robot's observation.
virtual double getProbMiss() const =0
std::string format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
void composePoint(double lx, double ly, double lz, double &gx, double &gy, double &gz, mrpt::math::CMatrixFixedNumeric< double, 3, 3 > *out_jacobian_df_dpoint=nullptr, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dpose=nullptr, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dse3=nullptr, bool use_small_rot_approx=false) const
An alternative, slightly more efficient way of doing with G and L being 3D points and P this 6D pose...
#define IS_CLASS(ptrObj, class_name)
Evaluates to true if the given pointer to an object (derived from mrpt::rtti::CObject) is of the give...
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string §ion) override
This method load the options from a ".ini"-like file or memory-stored string list.
std::vector< float > points3D_x
If hasPoints3D=true, the (X,Y,Z) coordinates of the 3D point cloud detected by the camera...
This class allows the user to create, load, save, and render 3D scenes using OpenGL primitives...
virtual void setOccupancyThres(double prob)=0
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream.
virtual double getProbHit() const =0
virtual void setClampingThresMax(double thresProb)=0
void insert(const CRenderizable::Ptr &newObject, const std::string &viewportName=std::string("main"))
Insert a new object into the scene, in the given viewport (by default, into the "main" viewport)...
size_t size() const
Returns the number of stored points in the map.
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot at the moment of starting the scan.
void getHomogeneousMatrix(mrpt::math::CMatrixDouble44 &out_HM) const
Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (t...
virtual void load() const override
Makes sure all images and other fields which may be externally stored are loaded in memory...