#include <octree_pa_node.h>
Public Types | |
typedef cOctreeBasePaNode< cOctreePaRos > | TypeBase |
![]() | |
typedef cOctreePaRos | TypeBase |
typedef cOctreeBasePaNode< cOctreePaRos > | TypeFull |
![]() | |
typedef cOctreeBasePaRos< OcTree > | TreeTypeBase |
![]() | |
typedef ::octomap::OcTreeKey | OctKey |
typedef pcl::PointCloud< pcl::PointXYZ > | PclPointCloud |
typedef pcl::PointCloud< pcl::PointXYZ >::ConstPtr | PclPointCloudConstPtr |
typedef pcl::PointCloud< pcl::PointXYZ >::Ptr | PclPointCloudPtr |
typedef octomap::OcTree | TreeTypeBase |
typedef cOctreeBasePaRos< octomap::OcTree > | TreeTypeFull |
![]() | |
typedef leaf_iterator | iterator |
typedef OcTreeNode | NodeType |
Public Member Functions | |
cOctreePaNode () | |
default constructor More... | |
~cOctreePaNode () | |
default destructor More... | |
![]() | |
cOctreeBasePaNode (const std::string nodename, const double resolution=0.1, const ros::Duration tf_listener_buffersize=ros::Duration(20)) | |
default constructor More... | |
virtual octomap_pa_msgs::Config | getConfig (void) |
function for retrieving all current configs More... | |
void | publishOctomap (void) |
function for publishing the octomap More... | |
virtual bool | setConfigDegrading (const octomap_pa_msgs::ConfigDegrading &config) |
function for setting degrading configs (does nothing by default More... | |
bool | setConfigInsertion (const octomap_pa_msgs::ConfigInsertion &config) |
function for setting config for adding pointclouds More... | |
virtual | ~cOctreeBasePaNode () |
default destructor More... | |
![]() | |
cOctreePaRos (const double resolution) | |
default constructor More... | |
virtual | ~cOctreePaRos () |
default destructor More... | |
![]() | |
bool | addCloud (const sensor_msgs::PointCloud2 &cloud, const cAddCloudParameter ¶ms, const tf::Transform transform=tf::Transform::getIdentity()) |
bool | addCloud (const sensor_msgs::PointCloud &cloud, const cAddCloudParameter ¶ms, const tf::Transform transform=tf::Transform::getIdentity()) |
bool | addCloud (const sensor_msgs::LaserScan &cloud, const cAddCloudParameter ¶ms, const tf::Transform transform=tf::Transform::getIdentity()) |
virtual void | clear (void) |
clear local timestamps with octomap More... | |
cOctreeBasePaRos (double resolution) | |
default constructor More... | |
bool | getChildKey (const OctKey ¤t, const int current_level, OctKey &child, const int child_pos) const |
virtual ros::Time | getLastInsertionTime (void) const |
function for returning the time the octomap was last updated More... | |
octomap_msgs::OctomapPtr | getOctomap (void) const |
function for getting the binary octomap More... | |
octomap_msgs::OctomapPtr | getOctomapFull (void) const |
function for getting the full octomap More... | |
sensor_msgs::PointCloud2Ptr | getOctomapPcd (const int tree_depth=0, const bool expand=false) const |
function for getting the pointcloud equivalent of the octomap More... | |
sensor_msgs::PointCloud2Ptr | getOctomapPcdFree (const int tree_depth=0, const bool expand=false) const |
similar to getOctomapPcd, but only returning just empty voxels More... | |
ros::Time | getOutputTime (void) const |
function for returning the time of output messages More... | |
bool | getParentKey (const OctKey ¤t, const int current_level, OctKey &parent) const |
geometry_msgs::PointPtr | keyToPoint (const OctKey &key) const |
function for converting from key to point (geometry_msg) More... | |
void | keyToPoint (const OctKey &key, double &x, double &y, double &z) const |
function for converting from key to real coordinates More... | |
OctKey | pointToKey (const geometry_msgs::Point &point) const |
functions for converting from point (geometry_msg) to key More... | |
bool | readFull (const std::string &filename) |
trying to read the given file into the current OcTree More... | |
virtual void | setLastInsertionTime (const ros::Time &time) |
void | setOutputTime (const ros::Time &time) |
bool | updateTime (const ros::Time &time) |
virtual | ~cOctreeBasePaRos () |
default destructor More... | |
![]() | |
OcTree * | create () const |
std::string | getTreeType () const |
OcTree (std::string _filename) | |
OcTree (double resolution) | |
virtual | ~OcTree () |
![]() | |
bool | bbxSet () const |
virtual bool | castRay (const point3d &origin, const point3d &direction, point3d &end, bool ignoreUnknownCells=false, double maxRange=-1.0) const |
KeyBoolMap::const_iterator | changedKeysBegin () const |
KeyBoolMap::const_iterator | changedKeysEnd () const |
void | computeDiscreteUpdate (const Pointcloud &scan, const octomap::point3d &origin, KeySet &free_cells, KeySet &occupied_cells, double maxrange) |
void | computeUpdate (const Pointcloud &scan, const octomap::point3d &origin, KeySet &free_cells, KeySet &occupied_cells, double maxrange) |
void | enableChangeDetection (bool enable) |
point3d | getBBXBounds () const |
point3d | getBBXCenter () const |
point3d | getBBXMax () const |
point3d | getBBXMin () const |
bool | getNormals (const point3d &point, std::vector< point3d > &normals, bool unknownStatus=true) const |
virtual bool | getRayIntersection (const point3d &origin, const point3d &direction, const point3d ¢er, point3d &intersection, double delta=0.0) const |
bool | inBBX (const point3d &p) const |
bool | inBBX (const OcTreeKey &key) const |
virtual void | insertPointCloud (const Pointcloud &scan, const octomap::point3d &sensor_origin, double maxrange=-1., bool lazy_eval=false, bool discretize=false) |
virtual void | insertPointCloud (const Pointcloud &scan, const point3d &sensor_origin, const pose6d &frame_origin, double maxrange=-1., bool lazy_eval=false, bool discretize=false) |
virtual void | insertPointCloud (const ScanNode &scan, double maxrange=-1., bool lazy_eval=false, bool discretize=false) |
virtual void | insertPointCloudRays (const Pointcloud &scan, const point3d &sensor_origin, double maxrange=-1., bool lazy_eval=false) |
virtual bool | insertRay (const point3d &origin, const point3d &end, double maxrange=-1.0, bool lazy_eval=false) |
virtual void | integrateHit (OcTreeNode *occupancyNode) const |
virtual void | integrateMiss (OcTreeNode *occupancyNode) const |
bool | isChangeDetectionEnabled () const |
virtual void | nodeToMaxLikelihood (OcTreeNode *occupancyNode) const |
virtual void | nodeToMaxLikelihood (OcTreeNode &occupancyNode) const |
size_t | numChangesDetected () const |
OccupancyOcTreeBase (double resolution) | |
OccupancyOcTreeBase (const OccupancyOcTreeBase< OcTreeNode > &rhs) | |
std::istream & | readBinaryData (std::istream &s) |
std::istream & | readBinaryNode (std::istream &s, OcTreeNode *node) |
void | resetChangeDetection () |
void | setBBXMax (point3d &max) |
void | setBBXMin (point3d &min) |
virtual OcTreeNode * | setNodeValue (const point3d &value, float log_odds_value, bool lazy_eval=false) |
virtual OcTreeNode * | setNodeValue (const OcTreeKey &key, float log_odds_value, bool lazy_eval=false) |
virtual OcTreeNode * | setNodeValue (double x, double y, double z, float log_odds_value, bool lazy_eval=false) |
virtual void | toMaxLikelihood () |
void | updateInnerOccupancy () |
virtual OcTreeNode * | updateNode (double x, double y, double z, bool occupied, bool lazy_eval=false) |
virtual OcTreeNode * | updateNode (const point3d &value, bool occupied, bool lazy_eval=false) |
virtual OcTreeNode * | updateNode (const point3d &value, float log_odds_update, bool lazy_eval=false) |
virtual OcTreeNode * | updateNode (double x, double y, double z, float log_odds_update, bool lazy_eval=false) |
virtual OcTreeNode * | updateNode (const OcTreeKey &key, float log_odds_update, bool lazy_eval=false) |
virtual OcTreeNode * | updateNode (const OcTreeKey &key, bool occupied, bool lazy_eval=false) |
virtual void | updateNodeLogOdds (OcTreeNode *occupancyNode, const float &update) const |
void | useBBXLimit (bool enable) |
std::ostream & | writeBinaryData (std::ostream &s) const |
std::ostream & | writeBinaryNode (std::ostream &s, const OcTreeNode *node) const |
virtual | ~OccupancyOcTreeBase () |
![]() | |
OcTreeKey | adjustKeyAtDepth (const OcTreeKey &key, unsigned int depth) const |
key_type | adjustKeyAtDepth (key_type key, unsigned int depth) const |
iterator | begin (unsigned char maxDepth=0) const |
leaf_iterator | begin_leafs (unsigned char maxDepth=0) const |
leaf_bbx_iterator | begin_leafs_bbx (const OcTreeKey &min, const OcTreeKey &max, unsigned char maxDepth=0) const |
leaf_bbx_iterator | begin_leafs_bbx (const point3d &min, const point3d &max, unsigned char maxDepth=0) const |
tree_iterator | begin_tree (unsigned char maxDepth=0) const |
size_t | calcNumNodes () const |
void | clearKeyRays () |
bool | computeRay (const point3d &origin, const point3d &end, std::vector< point3d > &ray) |
bool | computeRayKeys (const point3d &origin, const point3d &end, KeyRay &ray) const |
OcTreeKey | coordToKey (double x, double y, double z) const |
OcTreeKey | coordToKey (const point3d &coord, unsigned depth) const |
OcTreeKey | coordToKey (double x, double y, double z, unsigned depth) const |
key_type | coordToKey (double coordinate) const |
key_type | coordToKey (double coordinate, unsigned depth) const |
OcTreeKey | coordToKey (const point3d &coord) const |
bool | coordToKeyChecked (const point3d &coord, OcTreeKey &key) const |
bool | coordToKeyChecked (const point3d &coord, unsigned depth, OcTreeKey &key) const |
bool | coordToKeyChecked (double x, double y, double z, OcTreeKey &key) const |
bool | coordToKeyChecked (double x, double y, double z, unsigned depth, OcTreeKey &key) const |
bool | coordToKeyChecked (double coordinate, key_type &key) const |
bool | coordToKeyChecked (double coordinate, unsigned depth, key_type &key) const |
OcTreeNode * | createNodeChild (OcTreeNode *node, unsigned int childIdx) |
bool | deleteNode (double x, double y, double z, unsigned int depth=0) |
bool | deleteNode (const point3d &value, unsigned int depth=0) |
bool | deleteNode (const OcTreeKey &key, unsigned int depth=0) |
void | deleteNodeChild (OcTreeNode *node, unsigned int childIdx) |
const iterator | end () const |
const leaf_iterator | end_leafs () const |
const leaf_bbx_iterator | end_leafs_bbx () const |
const tree_iterator | end_tree () const |
virtual void | expand () |
virtual void | expandNode (OcTreeNode *node) |
virtual void | getMetricMax (double &x, double &y, double &z) |
void | getMetricMax (double &x, double &y, double &z) const |
virtual void | getMetricMin (double &x, double &y, double &z) |
void | getMetricMin (double &x, double &y, double &z) const |
virtual void | getMetricSize (double &x, double &y, double &z) |
virtual void | getMetricSize (double &x, double &y, double &z) const |
const OcTreeNode * | getNodeChild (const OcTreeNode *node, unsigned int childIdx) const |
OcTreeNode * | getNodeChild (OcTreeNode *node, unsigned int childIdx) const |
double | getNodeSize (unsigned depth) const |
size_t | getNumLeafNodes () const |
double | getResolution () const |
OcTreeNode * | getRoot () const |
unsigned int | getTreeDepth () const |
std::string | getTreeType () const |
void | getUnknownLeafCenters (point3d_list &node_centers, point3d pmin, point3d pmax, unsigned int depth=0) const |
virtual bool | isNodeCollapsible (const OcTreeNode *node) const |
point3d | keyToCoord (const OcTreeKey &key) const |
point3d | keyToCoord (const OcTreeKey &key, unsigned depth) const |
double | keyToCoord (key_type key) const |
double | keyToCoord (key_type key, unsigned depth) const |
unsigned long long | memoryFullGrid () const |
virtual size_t | memoryUsage () const |
virtual size_t | memoryUsageNode () const |
bool | nodeChildExists (const OcTreeNode *node, unsigned int childIdx) const |
bool | nodeHasChildren (const OcTreeNode *node) const |
OcTreeBaseImpl (const OcTreeBaseImpl< OcTreeNode, AbstractOccupancyOcTree > &rhs) | |
OcTreeBaseImpl (double resolution) | |
bool | operator== (const OcTreeBaseImpl< OcTreeNode, AbstractOccupancyOcTree > &rhs) const |
virtual void | prune () |
virtual bool | pruneNode (OcTreeNode *node) |
std::istream & | readData (std::istream &s) |
OcTreeNode * | search (const point3d &value, unsigned int depth=0) const |
OcTreeNode * | search (const OcTreeKey &key, unsigned int depth=0) const |
OcTreeNode * | search (double x, double y, double z, unsigned int depth=0) const |
void | setResolution (double r) |
virtual size_t | size () const |
void | swapContent (OcTreeBaseImpl< OcTreeNode, AbstractOccupancyOcTree > &rhs) |
double | volume () |
std::ostream & | writeData (std::ostream &s) const |
virtual | ~OcTreeBaseImpl () |
![]() | |
AbstractOccupancyOcTree () | |
double | getClampingThresMax () const |
float | getClampingThresMaxLog () const |
double | getClampingThresMin () const |
float | getClampingThresMinLog () const |
double | getOccupancyThres () const |
float | getOccupancyThresLog () const |
double | getProbHit () const |
float | getProbHitLog () const |
double | getProbMiss () const |
float | getProbMissLog () const |
bool | isNodeAtThreshold (const OcTreeNode *occupancyNode) const |
bool | isNodeAtThreshold (const OcTreeNode &occupancyNode) const |
bool | isNodeOccupied (const OcTreeNode *occupancyNode) const |
bool | isNodeOccupied (const OcTreeNode &occupancyNode) const |
bool | readBinary (std::istream &s) |
bool | readBinary (const std::string &filename) |
void | setClampingThresMax (double thresProb) |
void | setClampingThresMin (double thresProb) |
void | setOccupancyThres (double prob) |
void | setProbHit (double prob) |
void | setProbMiss (double prob) |
virtual OcTreeNode * | updateNode (const OcTreeKey &key, float log_odds_update, bool lazy_eval=false)=0 |
virtual OcTreeNode * | updateNode (const OcTreeKey &key, bool occupied, bool lazy_eval=false)=0 |
bool | writeBinary (const std::string &filename) |
bool | writeBinary (std::ostream &s) |
bool | writeBinaryConst (std::ostream &s) const |
bool | writeBinaryConst (const std::string &filename) const |
virtual | ~AbstractOccupancyOcTree () |
![]() | |
AbstractOcTree () | |
bool | write (std::ostream &s) const |
bool | write (const std::string &filename) const |
virtual | ~AbstractOcTree () |
Static Public Attributes | |
static const std::string | nodename_ = "octree_pa_node" |
official node name More... | |
Protected Member Functions | |
virtual void | internal_node_update (void) |
virtual overload for additional updates More... | |
![]() | |
bool | addCloudCallbackSrv (octomap_pa_msgs::AddCloud::Request &req, octomap_pa_msgs::AddCloud::Response &res) |
bool | addCloudTfCallbackSrv (octomap_pa_msgs::AddCloudTf::Request &req, octomap_pa_msgs::AddCloudTf::Response &res) |
void | addLaserCallbackSub (const sensor_msgs::LaserScanConstPtr &msg) |
callback function for receiving a laserscan More... | |
void | addPointcloudCallbackSub (const sensor_msgs::PointCloud2ConstPtr &msg) |
callback function for receiving a pointcloud More... | |
void | addPointcloudOldCallbackSub (const sensor_msgs::PointCloudConstPtr &msg) |
callback function for receiving a pointcloud (old format) More... | |
bool | clearCallbackSrv (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res) |
bool | getCloudCallbackSrv (octomap_pa_msgs::GetCloud::Request &req, octomap_pa_msgs::GetCloud::Response &res) |
bool | getConfigCallbackSrv (octomap_pa_msgs::GetConfig::Request &req, octomap_pa_msgs::GetConfig::Response &res) |
bool | getSizeCallbackSrv (octomap_pa_msgs::GetSize::Request &req, octomap_pa_msgs::GetSize::Response &res) |
bool | loadCallbackSrv (octomap_pa_msgs::FileName::Request &req, octomap_pa_msgs::FileName::Response &res) |
bool | resetCallbackSrv (octomap_pa_msgs::Reset::Request &req, octomap_pa_msgs::Reset::Response &res) |
bool | saveCallbackSrv (octomap_pa_msgs::FileName::Request &req, octomap_pa_msgs::FileName::Response &res) |
bool | setConfigDegradingCallbackSrv (octomap_pa_msgs::SetConfigDegrading::Request &req, octomap_pa_msgs::SetConfigDegrading::Response &res) |
bool | setConfigInsertionCallbackSrv (octomap_pa_msgs::SetConfigInsertion::Request &req, octomap_pa_msgs::SetConfigInsertion::Response &res) |
bool | updateTimeAndGetTF (const std_msgs::Header header, tf::Transform &transform) |
helper function to update/check timestamps & check/retrieve TF More... | |
![]() | |
bool | addCloud (const PclPointCloudPtr &cloud, const cAddCloudParameter ¶ms, const tf::Transform &transform) |
void | getChildKeySimple (const OctKey ¤t, const int current_level, OctKey &child, const int child_pos) const |
helper function for getChildKey More... | |
void | getOctomapPcdSub (const OctKey &key, const int current_level, const int min_level, PclPointCloud &cloud) const |
helper function for getOctomapPcd... More... | |
void | getParentKeySimple (const OctKey ¤t, const int current_level, OctKey &parent) const |
helper function for getParentKey More... | |
![]() | |
bool | integrateMissOnRay (const point3d &origin, const point3d &end, bool lazy_eval=false) |
OccupancyOcTreeBase (double resolution, unsigned int tree_depth, unsigned int tree_max_val) | |
OcTreeNode * | setNodeValueRecurs (OcTreeNode *node, bool node_just_created, const OcTreeKey &key, unsigned int depth, const float &log_odds_value, bool lazy_eval=false) |
void | toMaxLikelihoodRecurs (OcTreeNode *node, unsigned int depth, unsigned int max_depth) |
void | updateInnerOccupancyRecurs (OcTreeNode *node, unsigned int depth) |
OcTreeNode * | updateNodeRecurs (OcTreeNode *node, bool node_just_created, const OcTreeKey &key, unsigned int depth, const float &log_odds_update, bool lazy_eval=false) |
![]() | |
void | allocNodeChildren (OcTreeNode *node) |
void | calcMinMax () |
void | calcNumNodesRecurs (OcTreeNode *node, size_t &num_nodes) const |
void | deleteNodeRecurs (OcTreeNode *node) |
bool | deleteNodeRecurs (OcTreeNode *node, unsigned int depth, unsigned int max_depth, const OcTreeKey &key) |
void | expandRecurs (OcTreeNode *node, unsigned int depth, unsigned int max_depth) |
size_t | getNumLeafNodesRecurs (const OcTreeNode *parent) const |
void | init () |
OcTreeBaseImpl (double resolution, unsigned int tree_depth, unsigned int tree_max_val) | |
void | pruneRecurs (OcTreeNode *node, unsigned int depth, unsigned int max_depth, unsigned int &num_pruned) |
std::istream & | readNodesRecurs (OcTreeNode *, std::istream &s) |
std::ostream & | writeNodesRecurs (const OcTreeNode *, std::ostream &s) const |
![]() | |
bool | readBinaryLegacyHeader (std::istream &s, unsigned int &size, double &res) |
Additional Inherited Members | |
![]() | |
static AbstractOcTree * | createTree (const std::string id, double res) |
static AbstractOcTree * | read (std::istream &s) |
static AbstractOcTree * | read (const std::string &filename) |
![]() | |
cOctreeBasePaRosParameter | rosparams_base_ |
parameters More... | |
![]() | |
static bool | readHeader (std::istream &s, std::string &id, unsigned &size, double &res) |
static void | registerTreeType (AbstractOcTree *tree) |
![]() | |
cAddCloudParameter | addparams_ |
int | count_cloud_ |
number of inserted pointclouds More... | |
int | count_cloud_old_ |
number of inserted pointclouds (old format) More... | |
int | count_laser_ |
number of inserted laser scans More... | |
ros::NodeHandle | nh_ |
node handler for topic subscription and advertising More... | |
cOctreeBasePaNodeParameter | nodeparams_ |
parameters More... | |
ros::Publisher | pub_cloud_free_ |
puplisher for free voxels as pointcloud More... | |
ros::Publisher | pub_cloud_occupied_ |
puplisher for occupied voxels as pointcloud More... | |
ros::Publisher | pub_octomap_ |
puplisher for the octomap (binary data) More... | |
ros::Publisher | pub_octomap_full_ |
puplisher for the octomap (full data) More... | |
ros::ServiceServer | srv_addcloud_ |
service for adding a new pointcloud to the octomap More... | |
ros::ServiceServer | srv_addcloudtf_ |
service for adding a new pointcloud to the octomap (by passing a tf) More... | |
ros::ServiceServer | srv_clear_ |
service for clearing the octomap More... | |
ros::ServiceServer | srv_getcloud_ |
service for receiving the current octomap as pointcloud More... | |
ros::ServiceServer | srv_getconfig_ |
service for receiving all config of the octomap More... | |
ros::ServiceServer | srv_getsize_ |
service for receiving the current size of the octomap More... | |
ros::ServiceServer | srv_load_ |
service for loading a octomap More... | |
ros::ServiceServer | srv_reset_ |
ros::ServiceServer | srv_save_ |
service for saving the octomap More... | |
ros::ServiceServer | srv_setconfig_degrading_ |
service for setting the degrading config of the octomap More... | |
ros::ServiceServer | srv_setconfig_insertion_ |
service for setting the insertion config of the octomap More... | |
ros::Subscriber | sub_cloud_ |
subscriber for a pointcloud More... | |
ros::Subscriber | sub_cloud_old_ |
subscriber for a pointcloud (old format) More... | |
ros::Subscriber | sub_laser_ |
subscriber for a laserscan More... | |
tf::TransformListener | tf_listener_ |
transformation of different frames More... | |
![]() | |
ros::Time | current_output_time_ |
internal variable for storing current output time More... | |
ros::Time | last_insertion_time_ |
internal variable for storing last insertion time More... | |
![]() | |
point3d | bbx_max |
OcTreeKey | bbx_max_key |
point3d | bbx_min |
OcTreeKey | bbx_min_key |
KeyBoolMap | changed_keys |
bool | use_bbx_limit |
bool | use_change_detection |
![]() | |
std::vector< KeyRay > | keyrays |
const leaf_bbx_iterator | leaf_iterator_bbx_end |
const leaf_iterator | leaf_iterator_end |
double | max_value [3] |
double | min_value [3] |
double | resolution |
double | resolution_factor |
OcTreeNode * | root |
bool | size_changed |
std::vector< double > | sizeLookupTable |
point3d | tree_center |
const unsigned int | tree_depth |
const tree_iterator | tree_iterator_end |
const unsigned int | tree_max_val |
size_t | tree_size |
![]() | |
float | clamping_thres_max |
float | clamping_thres_min |
float | occ_prob_thres_log |
float | prob_hit_log |
float | prob_miss_log |
![]() | |
static StaticMemberInitializer | ocTreeMemberInit |
![]() | |
static const std::string | binaryFileHeader |
![]() | |
static const std::string | fileHeader |
Definition at line 60 of file octree_pa_node.h.
Definition at line 62 of file octree_pa_node.h.
cOctreePaNode::cOctreePaNode | ( | ) |
default constructor
Definition at line 72 of file octree_pa_node.cpp.
cOctreePaNode::~cOctreePaNode | ( | ) |
default destructor
Definition at line 78 of file octree_pa_node.cpp.
|
protectedvirtual |
virtual overload for additional updates
Implements cOctreeBasePaNode< cOctreePaRos >.
Definition at line 83 of file octree_pa_node.cpp.
|
static |
official node name
Definition at line 71 of file octree_pa_node.h.