20 template <
class OCTREE,
class OCTREE_NODE>
25 octomap::Pointcloud& scan)
const 34 robotPose3D = (*robotPose);
51 octomap::point3d(sensorPose.
x(), sensorPose.
y(), sensorPose.z());
55 const size_t nPts = scanPts->
size();
61 for (
size_t i = 0; i < nPts; i++)
64 scanPts->getPointFast(i, pt.
x, pt.
y, pt.
z);
71 scan.push_back(gx, gy, gz);
91 octomap::point3d(sensorPose.
x(), sensorPose.
y(), sensorPose.z());
95 const size_t sizeRangeScan = o->
points3D_x.size();
98 scan.reserve(sizeRangeScan);
103 const float m00 = H.get_unsafe(0, 0);
104 const float m01 = H.get_unsafe(0, 1);
105 const float m02 = H.get_unsafe(0, 2);
106 const float m03 = H.get_unsafe(0, 3);
107 const float m10 = H.get_unsafe(1, 0);
108 const float m11 = H.get_unsafe(1, 1);
109 const float m12 = H.get_unsafe(1, 2);
110 const float m13 = H.get_unsafe(1, 3);
111 const float m20 = H.get_unsafe(2, 0);
112 const float m21 = H.get_unsafe(2, 1);
113 const float m22 = H.get_unsafe(2, 2);
114 const float m23 = H.get_unsafe(2, 3);
117 for (
size_t i = 0; i < sizeRangeScan; i++)
124 if (pt.
x != 0 || pt.
y != 0 || pt.
z != 0)
127 const float gx = m00 * pt.
x + m01 * pt.
y + m02 * pt.
z + m03;
128 const float gy = m10 * pt.
x + m11 * pt.
y + m12 * pt.
z + m13;
129 const float gz = m20 * pt.
x + m21 * pt.
y + m22 * pt.
z + m23;
132 scan.push_back(gx, gy, gz);
141 template <
class OCTREE,
class OCTREE_NODE>
144 return m_octomap.size() == 1;
147 template <
class OCTREE,
class OCTREE_NODE>
157 mrpt::make_aligned_shared<mrpt::opengl::CSetOfObjects>();
159 this->getAs3DObject(obj3D);
171 const_cast<OCTREE*
>(&m_octomap)->writeBinary(fil);
176 template <
class OCTREE,
class OCTREE_NODE>
180 octomap::point3d sensorPt;
181 octomap::Pointcloud scan;
183 if (!internal_build_PointCloud_for_observation(
184 obs, &takenFrom, sensorPt, scan))
187 octomap::OcTreeKey key;
188 const size_t N = scan.size();
191 for (
size_t i = 0; i < N; i += likelihoodOptions.decimation)
193 if (m_octomap.coordToKeyChecked(scan.getPoint(i), key))
196 if (node) log_lik += std::log(node->getOccupancy());
203 template <
class OCTREE,
class OCTREE_NODE>
205 const float x,
const float y,
const float z,
double& prob_occupancy)
const 207 octomap::OcTreeKey key;
208 if (m_octomap.coordToKeyChecked(octomap::point3d(
x,
y,
z), key))
211 if (!node)
return false;
213 prob_occupancy = node->getOccupancy();
220 template <
class OCTREE,
class OCTREE_NODE>
222 const CPointsMap& ptMap,
const float sensor_x,
const float sensor_y,
223 const float sensor_z)
226 const octomap::point3d sensorPt(sensor_x, sensor_y, sensor_z);
228 const float *xs, *ys, *zs;
230 for (
size_t i = 0; i < N; i++)
232 sensorPt, octomap::point3d(xs[i], ys[i], zs[i]),
233 insertionOptions.maxrange, insertionOptions.pruning);
237 template <
class OCTREE,
class OCTREE_NODE>
242 octomap::point3d _end;
244 const bool ret = m_octomap.castRay(
245 octomap::point3d(origin.
x, origin.
y, origin.
z),
246 octomap::point3d(direction.
x, direction.
y, direction.
z), _end,
247 ignoreUnknownCells, maxRange);
258 template <
class OCTREE,
class OCTREE_NODE>
268 clampingThresMin(0.1192),
269 clampingThresMax(0.971)
273 template <
class OCTREE,
class OCTREE_NODE>
282 clampingThresMin(0.1192),
283 clampingThresMax(0.971)
287 template <
class OCTREE,
class OCTREE_NODE>
293 template <
class OCTREE,
class OCTREE_NODE>
302 template <
class OCTREE,
class OCTREE_NODE>
323 template <
class OCTREE,
class OCTREE_NODE>
328 "\n----------- [COctoMapBase<>::TInsertionOptions] ------------ \n\n");
342 template <
class OCTREE,
class OCTREE_NODE>
347 "\n----------- [COctoMapBase<>::TLikelihoodOptions] ------------ \n\n");
355 template <
class OCTREE,
class OCTREE_NODE>
369 this->setOccupancyThres(occupancyThres);
370 this->setProbHit(probHit);
371 this->setProbMiss(probMiss);
372 this->setClampingThresMin(clampingThresMin);
373 this->setClampingThresMax(clampingThresMax);
376 template <
class OCTREE,
class OCTREE_NODE>
384 template <
class OCTREE,
class OCTREE_NODE>
390 out << generateGridLines << generateOccupiedVoxels << visibleOccupiedVoxels
391 << generateFreeVoxels << visibleFreeVoxels;
394 template <
class OCTREE,
class OCTREE_NODE>
404 in >> generateGridLines >> generateOccupiedVoxels >>
405 visibleOccupiedVoxels >> generateFreeVoxels >>
bool getPointOccupancy(const float x, const float y, const float z, double &prob_occupancy) const
Get the occupancy probability [0,1] of a point.
virtual double internal_computeObservationLikelihood(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D &takenFrom) override
Internal method called by computeObservationLikelihood()
double x() const
Common members of all points & poses classes.
virtual void saveMetricMapRepresentationToFile(const std::string &filNamePrefix) const override
This virtual method saves the map to a file "filNamePrefix"+< some_file_extension >...
void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source, const std::string §ion) override
This method load the options from a ".ini"-like file or memory-stored string list.
const POINTSMAP * buildAuxPointsMap(const void *options=nullptr) const
Returns a cached points map representing this laser scan, building it upon the first call...
void writeToStream(mrpt::utils::CStream &out) const
Binary dump to stream.
#define LOADABLEOPTS_DUMP_VAR(variableName, variableType)
Macro for dumping a variable to a stream, within the method "dumpToTextStream(out)" (Variable types a...
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.
void dumpToTextStream(mrpt::utils::CStream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a CStream.
octomap::OcTreeNode octree_node_t
The type of nodes in the octree, in the "octomap" library.
This class allows loading and storing values and vectors of different types from a configuration text...
std::vector< float > points3D_z
A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ ...
TLikelihoodOptions()
Initilization of default parameters.
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans or other sensors...
void writeToStream(mrpt::utils::CStream &out) const
Binary dump to stream.
A numeric matrix of compile-time fixed size.
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...
This CStream derived class allow using a file as a write-only, binary stream.
bool internal_build_PointCloud_for_observation(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D *robotPose, octomap::point3d &point3d_sensorPt, octomap::Pointcloud &ptr_scan) const
Builds the list of 3D points in global coordinates for a generic observation.
#define MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(__V)
For use in CSerializable implementations.
void dumpToTextStream(mrpt::utils::CStream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a CStream.
std::shared_ptr< CSetOfObjects > Ptr
This namespace contains representation of robot actions and observations.
double x
X,Y,Z coordinates.
TInsertionOptions()
Especial constructor, not attached to a real COctoMap object: used only in limited situations...
void readFromStream(mrpt::utils::CStream &in)
Binary dump to stream.
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...
virtual bool isEmpty() const override
Returns true if the map is empty/no observation has been inserted.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
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.
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::utils::CSerializable) is of t...
void insertPointCloud(const CPointsMap &ptMap, const float sensor_x, const float sensor_y, const float sensor_z)
Update the octomap with a 2D or 3D scan, given directly as a point cloud and the 3D location of the s...
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...
void readFromStream(mrpt::utils::CStream &in)
Binary dump to stream.
#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...
void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source, const std::string §ion) override
This method load the options from a ".ini"-like file or memory-stored string list.
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 int printf(const char *fmt,...) MRPT_printf_format_check(2
Writes a string to the stream in a textual form.
virtual void load() const override
Makes sure all images and other fields which may be externally stored are loaded in memory...