20 template <
class OCTREE,
class OCTREE_NODE>
21 template <
class octomap_po
int3d,
class octomap_po
intcloud>
31 robotPose3D = (*robotPose);
45 sensorPt = octomap::point3d(sensorPose.
x(),sensorPose.
y(),sensorPose.z());
48 const size_t nPts = scanPts->
size();
54 for (
size_t i=0;i<nPts;i++)
57 scanPts->getPointFast(i,pt.
x,pt.
y,pt.
z);
64 scan.push_back(gx,gy,gz);
82 sensorPt = octomap::point3d(sensorPose.
x(),sensorPose.
y(),sensorPose.z());
85 const size_t sizeRangeScan = o->
points3D_x.size();
88 scan.reserve(sizeRangeScan);
93 const float m00 = H.get_unsafe(0,0);
94 const float m01 = H.get_unsafe(0,1);
95 const float m02 = H.get_unsafe(0,2);
96 const float m03 = H.get_unsafe(0,3);
97 const float m10 = H.get_unsafe(1,0);
98 const float m11 = H.get_unsafe(1,1);
99 const float m12 = H.get_unsafe(1,2);
100 const float m13 = H.get_unsafe(1,3);
101 const float m20 = H.get_unsafe(2,0);
102 const float m21 = H.get_unsafe(2,1);
103 const float m22 = H.get_unsafe(2,2);
104 const float m23 = H.get_unsafe(2,3);
107 for (
size_t i=0;i<sizeRangeScan;i++)
114 if ( pt.
x!=0 || pt.
y!=0 || pt.
z!=0 )
117 const float gx = m00*pt.
x + m01*pt.
y + m02*pt.
z + m03;
118 const float gy = m10*pt.
x + m11*pt.
y + m12*pt.
z + m13;
119 const float gz = m20*pt.
x + m21*pt.
y + m22*pt.
z + m23;
122 scan.push_back(gx,gy,gz);
131 template <
class OCTREE,
class OCTREE_NODE>
141 this->getAs3DObject(obj3D);
153 const_cast<OCTREE*
>(
PIMPL_GET_PTR(OCTREE, m_octomap))->writeBinary(fil);
158 template <
class OCTREE,
class OCTREE_NODE>
161 octomap::point3d sensorPt;
162 octomap::Pointcloud scan;
164 if (!internal_build_PointCloud_for_observation(obs,&takenFrom, sensorPt, scan))
167 octomap::OcTreeKey key;
168 const size_t N=scan.size();
171 for (
size_t i=0;i<N;i+=likelihoodOptions.decimation)
173 if (
PIMPL_GET_REF(OCTREE, m_octomap).coordToKeyChecked(scan.getPoint(i), key))
175 OCTREE_NODE *node =
PIMPL_GET_REF(OCTREE, m_octomap).search(key,0 );
177 log_lik += std::log(node->getOccupancy());
184 template <
class OCTREE,
class OCTREE_NODE>
187 octomap::OcTreeKey key;
188 if (
PIMPL_GET_REF(OCTREE, m_octomap).coordToKeyChecked(octomap::point3d(
x,
y,
z), key))
190 OCTREE_NODE *node =
PIMPL_GET_REF(OCTREE, m_octomap).search(key,0 );
191 if (!node)
return false;
193 prob_occupancy = node->getOccupancy();
199 template <
class OCTREE,
class OCTREE_NODE>
203 const octomap::point3d sensorPt(sensor_x,sensor_y,sensor_z);
205 const float *xs,*ys,*zs;
207 for (
size_t i=0;i<N;i++)
208 PIMPL_GET_REF(OCTREE, m_octomap).insertRay(sensorPt, octomap::point3d(xs[i],ys[i],zs[i]), insertionOptions.maxrange,insertionOptions.pruning);
212 template <
class OCTREE,
class OCTREE_NODE>
215 octomap::point3d _end;
218 octomap::point3d(origin.
x,origin.
y,origin.
z),
219 octomap::point3d(direction.
x,direction.
y,direction.
z),
220 _end,ignoreUnknownCells,maxRange);
233 template <
class OCTREE,
class OCTREE_NODE>
239 occupancyThres (0.5),
242 clampingThresMin(0.1192),
243 clampingThresMax(0.971)
247 template <
class OCTREE,
class OCTREE_NODE>
253 occupancyThres (0.5),
256 clampingThresMin(0.1192),
257 clampingThresMax(0.971)
261 template <
class OCTREE,
class OCTREE_NODE>
267 template <
class OCTREE,
class OCTREE_NODE>
275 template <
class OCTREE,
class OCTREE_NODE>
295 template <
class OCTREE,
class OCTREE_NODE>
298 out.
printf(
"\n----------- [COctoMapBase<>::TInsertionOptions] ------------ \n\n");
312 template <
class OCTREE,
class OCTREE_NODE>
315 out.
printf(
"\n----------- [COctoMapBase<>::TLikelihoodOptions] ------------ \n\n");
323 template <
class OCTREE,
class OCTREE_NODE>
345 template <
class OCTREE,
class OCTREE_NODE>
354 template <
class OCTREE,
class OCTREE_NODE>
359 out << generateGridLines << generateOccupiedVoxels << visibleOccupiedVoxels
360 << generateFreeVoxels << visibleFreeVoxels;
363 template <
class OCTREE,
class OCTREE_NODE>
372 in >> generateGridLines >> generateOccupiedVoxels >> visibleOccupiedVoxels
373 >> generateFreeVoxels >> visibleFreeVoxels;
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 void saveMetricMapRepresentationToFile(const std::string &filNamePrefix) const MRPT_OVERRIDE
This virtual method saves the map to a file "filNamePrefix"+< some_file_extension >...
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
void dumpToTextStream(mrpt::utils::CStream &out) const MRPT_OVERRIDE
This method should clearly display all the contents of the structure in textual form, sending it to a CStream.
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.
virtual void setProbHit(double prob)=0
virtual double getClampingThresMax() const =0
double z
X,Y,Z coordinates.
virtual double internal_computeObservationLikelihood(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D &takenFrom) MRPT_OVERRIDE
Internal method called by computeObservationLikelihood()
This class allows loading and storing values and vectors of different types from a configuration text...
std::vector< float > points3D_z
If hasPoints3D=true, the (X,Y,Z) coordinates of the 3D point cloud detected by the camera...
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.
void composePoint(double lx, double ly, double lz, double &gx, double &gy, double &gz, mrpt::math::CMatrixFixedNumeric< double, 3, 3 > *out_jacobian_df_dpoint=NULL, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dpose=NULL, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dse3=NULL, 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...
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.
void insert(const CRenderizablePtr &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)...
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.
void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source, const std::string §ion) MRPT_OVERRIDE
This method load the options from a ".ini"-like file or memory-stored string list.
#define MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(__V)
For use in CSerializable implementations.
bool internal_build_PointCloud_for_observation(const mrpt::obs::CObservation *obs, const mrpt::poses::CPose3D *robotPose, octomap_point3d &sensorPt, octomap_pointcloud &scan) const
Builds the list of 3D points in global coordinates for a generic observation.
#define PIMPL_GET_PTR(_TYPE, _VAR_NAME)
This namespace contains representation of robot actions and observations.
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
#define PIMPL_GET_REF(_TYPE, _VAR_NAME)
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...
#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...
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 NULL if there is no points in the map.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source, const std::string §ion) MRPT_OVERRIDE
This method load the options from a ".ini"-like file or memory-stored string list.
Declares a class that represents any robot's observation.
virtual double getProbMiss() const =0
#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
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.
virtual void setOccupancyThres(double prob)=0
virtual double getProbHit() const =0
void dumpToTextStream(mrpt::utils::CStream &out) const MRPT_OVERRIDE
This method should clearly display all the contents of the structure in textual form, sending it to a CStream.
virtual void load() const MRPT_OVERRIDE
Makes sure all images and other fields which may be externally stored are loaded in memory...
virtual void setClampingThresMax(double thresProb)=0
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.
static CSetOfObjectsPtr Create()
const POINTSMAP * buildAuxPointsMap(const void *options=NULL) const
Returns a cached points map representing this laser scan, building it upon the first call...