Go to the documentation of this file.
44 template <
class octree_t,
class octree_node_t>
60 template <
class OCTOMAP_CLASS>
85 const bool o_has_parent = o.
m_parent.get() !=
nullptr;
99 const std::string& section)
override;
101 std::ostream&
out)
const override;
146 return m_parent->getOccupancyThres();
153 return m_parent->getOccupancyThresLog();
181 return m_parent->getClampingThresMin();
189 return m_parent->getClampingThresMinLog();
196 return m_parent->getClampingThresMax();
204 return m_parent->getClampingThresMaxLog();
241 const std::string& section)
override;
243 std::ostream&
out)
const override;
257 const std::string& filNamePrefix)
const override;
299 outObj->insert(gl_obj);
313 const float x,
const float y,
const float z,
314 double& prob_occupancy)
const;
324 const CPointsMap& ptMap,
const float sensor_x,
const float sensor_y,
325 const float sensor_z);
348 bool ignoreUnknownCells =
false,
double maxRange = -1.0)
const;
374 template <
class octomap_po
int3d,
class octomap_po
intcloud>
378 octomap_pointcloud& scan)
const;
virtual float getProbHitLog() const =0
TRenderingOptions()=default
generateFreeVoxels=true) (Default=true)
void setOccupancyThres(double prob)
insertion (default: true)
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.
TInsertionOptions insertionOptions
The options used when inserting.
const_iterator end() const
virtual void setProbHit(double prob)=0
virtual float getProbMissLog() const =0
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::shared_ptr< mrpt::opengl ::CSetOfObjects > Ptr
TLikelihoodOptions likelihoodOptions
float getProbMissLog() const
void readFromStream(mrpt::serialization::CArchive &in)
Binary dump to stream.
double internal_computeObservationLikelihood(const mrpt::obs::CObservation &obs, const mrpt::poses::CPose3D &takenFrom) override
Internal method called by computeObservationLikelihood()
virtual void setOccupancyThres(double prob)=0
void readFromStream(mrpt::serialization::CArchive &in)
Binary dump to stream.
virtual double getProbMiss() const =0
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form,...
float getClampingThresMaxLog() const
A cloud of points in 2D or 3D, which can be built from a sequence of laser scans or other sensors.
spimpl::impl_ptr< T > pimpl
void setClampingThresMin(double thresProb)
(key name in .ini files: "clampingThresMin")sets the minimum threshold for occupancy clamping (sensor...
mrpt::vision::TStereoCalibResults out
virtual float getClampingThresMaxLog() const =0
bool generateOccupiedVoxels
useful to draw the "structure" of the octree, but computationally costly (Default: false)
virtual float getClampingThresMinLog() const =0
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.
~TLikelihoodOptions() override=default
void writeToStream(mrpt::serialization::CArchive &out) const
Binary dump to stream.
double getProbHit() const
void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr &outObj) const override
Returns a 3D object representing the map.
Virtual base class for "archives": classes abstracting I/O streams.
A wrapper class for pointers whose copy operations from other objects of the same type are ignored,...
A three-dimensional probabilistic occupancy grid, implemented as an octo-tree with the "octomap" C++ ...
bool pruning
inserted (default -1: complete beam)
float getClampingThresMinLog() const
void saveMetricMapRepresentationToFile(const std::string &filNamePrefix) const override
This virtual method saves the map to a file "filNamePrefix"+< some_file_extension >,...
virtual double getClampingThresMin() const =0
void setProbHit(double prob)
(key name in .ini files: "probHit")sets the probablility for a "hit" (will be converted to logodds) -...
double getOccupancyThres() const
float getOccupancyThresLog() const
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().
mrpt::ignored_copy_ptr< myself_t > m_parent
Declares a virtual base class for all metric maps storage classes.
bool getPointOccupancy(const float x, const float y, const float z, double &prob_occupancy) const
Get the occupancy probability [0,1] of a point.
TInsertionOptions()
Special constructor, not attached to a real COctoMap object: used only in limited situations,...
TRenderingOptions renderingOptions
This class allows loading and storing values and vectors of different types from a configuration text...
double getClampingThresMax() const
double maxrange
maximum range for how long individual beams are
virtual void setProbMiss(double prob)=0
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
void setClampingThresMax(double thresProb)
(key name in .ini files: "clampingThresMax")sets the maximum threshold for occupancy clamping (sensor...
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
virtual double getClampingThresMax() const =0
uint32_t decimation
Speed up the likelihood computation by.
virtual void setClampingThresMax(double thresProb)=0
void setProbMiss(double prob)
(key name in .ini files: "probMiss")sets the probablility for a "miss" (will be converted to logodds)...
mrpt::pimpl< Impl > m_impl
void writeToStream(mrpt::serialization::CArchive &out) const
Binary dump to stream.
virtual double getProbHit() const =0
TInsertionOptions & operator=(const TInsertionOptions &o)
virtual float getOccupancyThresLog() const =0
virtual double getOccupancyThres() const =0
A flexible renderer of voxels, typically from a 3D octo map (see mrpt::maps::COctoMap).
bool visibleOccupiedVoxels
volumes (Default=true)
float getProbHitLog() const
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.
static Ptr Create(Args &&... args)
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form,...
OCTOMAP_CLASS & getOctomap()
Get a reference to the internal octomap object.
double getClampingThresMin() const
Declares a class that represents any robot's observation.
bool generateFreeVoxels
generateOccupiedVoxels=true) (Default=true)
virtual void getAsOctoMapVoxels(mrpt::opengl::COctoMapVoxels &gl_obj) const =0
Builds a renderizable representation of the octomap as a mrpt::opengl::COctoMapVoxels object.
bool generateGridLines
Generate grid lines for all octree nodes,.
double getProbMiss() const
Options for the conversion of a mrpt::maps::COctoMap into a mrpt::opengl::COctoMapVoxels.
~COctoMapBase() override=default
TInsertionOptions(const TInsertionOptions &o)
bool visibleFreeVoxels
(Default=true)
TLikelihoodOptions()
Initilization of default parameters.
COctoMapBase(double resolution)
Constructor, defines the resolution of the octomap (length of each voxel side)
With this struct options are provided to the observation insertion process.
virtual void setClampingThresMin(double thresProb)=0
Page generated by Doxygen 1.8.17 for MRPT 2.0.4 at Sat Jun 27 14:00:59 UTC 2020 | |