Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
cOctreePaNode Class Reference

#include <octree_pa_node.h>

Inheritance diagram for cOctreePaNode:
Inheritance graph
[legend]

Public Member Functions

 cOctreePaNode ()
 default constructor More...
 
void publishOctomap (void)
 function for publishing the octomap More...
 
 ~cOctreePaNode ()
 default destructor More...
 
- Public Member Functions inherited from cOctreePaRos
 cOctreePaRos (const double resolution)
 default constructor More...
 
virtual ~cOctreePaRos ()
 default destructor More...
 
- Public Member Functions inherited from cOctreeBasePaRos< octomap::OcTree >
bool addCloud (const sensor_msgs::PointCloud2ConstPtr &cloud, const cAddCloudParameter &params, const tf::Transform transform=tf::Transform::getIdentity())
 
bool addCloud (const sensor_msgs::PointCloudConstPtr &cloud, const cAddCloudParameter &params, const tf::Transform transform=tf::Transform::getIdentity())
 
bool addCloud (const sensor_msgs::LaserScanConstPtr &cloud, const cAddCloudParameter &params, 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 &current, const int current_level, OctKey &child, const int child_pos) const
 
virtual ros::Time getLastInsertionTime (void) const
 
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
 
bool getParentKey (const OctKey &current, 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...
 
- Public Member Functions inherited from octomap::OcTree
OcTreecreate () const
 
std::string getTreeType () const
 
 OcTree (std::string _filename)
 
 OcTree (double resolution)
 
virtual ~OcTree ()
 
- Public Member Functions inherited from OccupancyOcTreeBase< OcTreeNode >
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 &center, 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)
 
 OCTOMAP_DEPRECATED (virtual void insertScanNaive(const Pointcloud &scan, const point3d &sensor_origin, double maxrange, bool lazy_eval=false))
 
 OCTOMAP_DEPRECATED (virtual void insertScan(const ScanNode &scan, double maxrange=-1., bool pruning=true, bool lazy_eval=false))
 
 OCTOMAP_DEPRECATED (virtual void insertScan(const Pointcloud &scan, const octomap::point3d &sensor_origin, double maxrange=-1., bool pruning=true, bool lazy_eval=false))
 
 OCTOMAP_DEPRECATED (virtual void insertScan(const Pointcloud &scan, const point3d &sensor_origin, const pose6d &frame_origin, double maxrange=-1., bool pruning=true, bool lazy_eval=false))
 
std::istream & readBinaryData (std::istream &s)
 
std::istream & readBinaryNode (std::istream &s, OcTreeNode *node) const
 
void resetChangeDetection ()
 
void setBBXMax (point3d &max)
 
void setBBXMin (point3d &min)
 
virtual OcTreeNode * setNodeValue (const OcTreeKey &key, float log_odds_value, bool lazy_eval=false)
 
virtual OcTreeNode * setNodeValue (const point3d &value, 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, float log_odds_update, bool lazy_eval=false)
 
virtual OcTreeNode * updateNode (const OcTreeKey &key, bool occupied, bool lazy_eval=false)
 
virtual OcTreeNode * updateNode (const point3d &value, float log_odds_update, bool lazy_eval=false)
 
virtual OcTreeNode * updateNode (const point3d &value, bool occupied, bool lazy_eval=false)
 
virtual OcTreeNode * updateNode (double x, double y, double z, bool occupied, bool lazy_eval=false)
 
virtual OcTreeNode * updateNode (const OcTreeKey &key, float log_odds_update, 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 ()
 
- Public Member Functions inherited from OcTreeBaseImpl< OcTreeNode, AbstractOccupancyOcTree >
OcTreeKey adjustKeyAtDepth (const OcTreeKey &key, unsigned int depth) const
 
unsigned short int adjustKeyAtDepth (unsigned short int 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
 
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 (const point3d &coord, unsigned depth) const
 
OcTreeKey coordToKey (double x, double y, double z, unsigned depth) const
 
unsigned short int coordToKey (double coordinate) const
 
unsigned short int coordToKey (double coordinate, unsigned depth) const
 
OcTreeKey coordToKey (const point3d &coord) const
 
OcTreeKey coordToKey (double x, double y, double z) 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, unsigned short int &key) const
 
bool coordToKeyChecked (double coordinate, unsigned depth, unsigned short int &key) const
 
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)
 
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 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
 
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
 
point3d keyToCoord (const OcTreeKey &key) const
 
double keyToCoord (unsigned short int key, unsigned depth) const
 
double keyToCoord (unsigned short int key) const
 
point3d keyToCoord (const OcTreeKey &key, unsigned depth) const
 
unsigned long long memoryFullGrid () const
 
virtual size_t memoryUsage () const
 
virtual size_t memoryUsageNode () const
 
 OcTreeBaseImpl (const OcTreeBaseImpl< OcTreeNode, AbstractOccupancyOcTree > &rhs)
 
 OcTreeBaseImpl (double resolution)
 
bool operator== (const OcTreeBaseImpl< OcTreeNode, AbstractOccupancyOcTree > &rhs) const
 
virtual void prune ()
 
std::istream & readData (std::istream &s)
 
OcTreeNode * search (const OcTreeKey &key, unsigned int depth=0) const
 
OcTreeNode * search (const point3d &value, 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 ()
 
- Public Member Functions inherited from octomap::AbstractOccupancyOcTree
 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 OcTreeNodeupdateNode (const OcTreeKey &key, float log_odds_update, bool lazy_eval=false)=0
 
virtual OcTreeNodeupdateNode (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 ()
 
- Public Member Functions inherited from octomap::AbstractOcTree
 AbstractOcTree ()
 
bool write (std::ostream &s) const
 
bool write (const std::string &filename) const
 
virtual ~AbstractOcTree ()
 

Protected Member Functions

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 getSizeCallbackSrv (octomap_pa::OctomapPaGetSize::Request &req, octomap_pa::OctomapPaGetSize::Response &res)
 
bool loadCallbackSrv (octomap_pa::OctomapPaFileName::Request &req, octomap_pa::OctomapPaFileName::Response &res)
 
bool saveCallbackSrv (octomap_pa::OctomapPaFileName::Request &req, octomap_pa::OctomapPaFileName::Response &res)
 
- Protected Member Functions inherited from cOctreeBasePaRos< octomap::OcTree >
bool addCloud (const PclPointCloudPtr &cloud, const cAddCloudParameter &params, const tf::Transform &transform)
 
void getChildKeySimple (const OctKey &current, 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 &current, const int current_level, OctKey &parent) const
 helper function for getParentKey More...
 
- Protected Member Functions inherited from OccupancyOcTreeBase< OcTreeNode >
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)
 
- Protected Member Functions inherited from OcTreeBaseImpl< OcTreeNode, AbstractOccupancyOcTree >
void calcMinMax ()
 
void calcNumNodesRecurs (OcTreeNode *node, size_t &num_nodes) const
 
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)
 
- Protected Member Functions inherited from octomap::AbstractOccupancyOcTree
bool readBinaryLegacyHeader (std::istream &s, unsigned int &size, double &res)
 

Protected Attributes

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_clear_
 service for clearing the octomap More...
 
ros::ServiceServer srv_getsize_
 service for receiving the size of the octomap More...
 
ros::ServiceServer srv_load_
 service for loading a octomap More...
 
ros::ServiceServer srv_save_
 service for saving 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...
 
- Protected Attributes inherited from cOctreeBasePaRos< octomap::OcTree >
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...
 
- Protected Attributes inherited from OccupancyOcTreeBase< OcTreeNode >
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
 
- Protected Attributes inherited from OcTreeBaseImpl< OcTreeNode, AbstractOccupancyOcTree >
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
 
- Protected Attributes inherited from octomap::AbstractOccupancyOcTree
float clamping_thres_max
 
float clamping_thres_min
 
float occ_prob_thres_log
 
float prob_hit_log
 
float prob_miss_log
 

Additional Inherited Members

- Public Types inherited from cOctreePaRos
typedef cOctreeBasePaRos< OcTreeTreeTypeBase
 
- Public Types inherited from cOctreeBasePaRos< octomap::OcTree >
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::OcTreeTreeTypeFull
 
- Public Types inherited from OcTreeBaseImpl< OcTreeNode, AbstractOccupancyOcTree >
typedef leaf_iterator iterator
 
typedef OcTreeNode NodeType
 
- Static Public Member Functions inherited from octomap::AbstractOcTree
static AbstractOcTreecreateTree (const std::string id, double res)
 
static AbstractOcTreeread (std::istream &s)
 
static AbstractOcTreeread (const std::string &filename)
 
- Public Attributes inherited from cOctreeBasePaRos< octomap::OcTree >
cOctreeBasePaRosParameter rosparams_base_
 parameters More...
 
- Static Protected Member Functions inherited from octomap::AbstractOcTree
static bool readHeader (std::istream &s, std::string &id, unsigned &size, double &res)
 
static void registerTreeType (AbstractOcTree *tree)
 
- Static Protected Attributes inherited from octomap::OcTree
static StaticMemberInitializer ocTreeMemberInit
 
- Static Protected Attributes inherited from octomap::AbstractOccupancyOcTree
static const std::string binaryFileHeader
 
- Static Protected Attributes inherited from octomap::AbstractOcTree
static const std::string fileHeader
 

Detailed Description

Definition at line 82 of file octree_pa_node.h.

Constructor & Destructor Documentation

cOctreePaNode::cOctreePaNode ( )

default constructor

Definition at line 67 of file octree_pa_node.cpp.

cOctreePaNode::~cOctreePaNode ( )

default destructor

Definition at line 171 of file octree_pa_node.cpp.

Member Function Documentation

void cOctreePaNode::addLaserCallbackSub ( const sensor_msgs::LaserScanConstPtr &  msg)
protected

callback function for receiving a laserscan

Definition at line 248 of file octree_pa_node.cpp.

void cOctreePaNode::addPointcloudCallbackSub ( const sensor_msgs::PointCloud2ConstPtr &  msg)
protected

callback function for receiving a pointcloud

Definition at line 194 of file octree_pa_node.cpp.

void cOctreePaNode::addPointcloudOldCallbackSub ( const sensor_msgs::PointCloudConstPtr msg)
protected

callback function for receiving a pointcloud (old format)

Definition at line 221 of file octree_pa_node.cpp.

bool cOctreePaNode::clearCallbackSrv ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
)
protected

Definition at line 277 of file octree_pa_node.cpp.

bool cOctreePaNode::getSizeCallbackSrv ( octomap_pa::OctomapPaGetSize::Request &  req,
octomap_pa::OctomapPaGetSize::Response &  res 
)
protected

Definition at line 293 of file octree_pa_node.cpp.

bool cOctreePaNode::loadCallbackSrv ( octomap_pa::OctomapPaFileName::Request &  req,
octomap_pa::OctomapPaFileName::Response &  res 
)
protected

Definition at line 328 of file octree_pa_node.cpp.

void cOctreePaNode::publishOctomap ( void  )

function for publishing the octomap

Definition at line 176 of file octree_pa_node.cpp.

bool cOctreePaNode::saveCallbackSrv ( octomap_pa::OctomapPaFileName::Request &  req,
octomap_pa::OctomapPaFileName::Response &  res 
)
protected

Definition at line 310 of file octree_pa_node.cpp.

Member Data Documentation

cAddCloudParameter cOctreePaNode::addparams_
protected

Definition at line 97 of file octree_pa_node.h.

int cOctreePaNode::count_cloud_
protected

number of inserted pointclouds

Definition at line 100 of file octree_pa_node.h.

int cOctreePaNode::count_cloud_old_
protected

number of inserted pointclouds (old format)

Definition at line 102 of file octree_pa_node.h.

int cOctreePaNode::count_laser_
protected

number of inserted laser scans

Definition at line 104 of file octree_pa_node.h.

ros::NodeHandle cOctreePaNode::nh_
protected

node handler for topic subscription and advertising

Definition at line 107 of file octree_pa_node.h.

cOctreeBasePaNodeParameter cOctreePaNode::nodeparams_
protected

parameters

Definition at line 96 of file octree_pa_node.h.

ros::Publisher cOctreePaNode::pub_cloud_free_
protected

puplisher for free voxels as pointcloud

Definition at line 135 of file octree_pa_node.h.

ros::Publisher cOctreePaNode::pub_cloud_occupied_
protected

puplisher for occupied voxels as pointcloud

Definition at line 137 of file octree_pa_node.h.

ros::Publisher cOctreePaNode::pub_octomap_
protected

puplisher for the octomap (binary data)

Definition at line 131 of file octree_pa_node.h.

ros::Publisher cOctreePaNode::pub_octomap_full_
protected

puplisher for the octomap (full data)

Definition at line 133 of file octree_pa_node.h.

ros::ServiceServer cOctreePaNode::srv_clear_
protected

service for clearing the octomap

Definition at line 141 of file octree_pa_node.h.

ros::ServiceServer cOctreePaNode::srv_getsize_
protected

service for receiving the size of the octomap

Definition at line 146 of file octree_pa_node.h.

ros::ServiceServer cOctreePaNode::srv_load_
protected

service for loading a octomap

Definition at line 156 of file octree_pa_node.h.

ros::ServiceServer cOctreePaNode::srv_save_
protected

service for saving the octomap

Definition at line 151 of file octree_pa_node.h.

ros::Subscriber cOctreePaNode::sub_cloud_
protected

subscriber for a pointcloud

Definition at line 114 of file octree_pa_node.h.

ros::Subscriber cOctreePaNode::sub_cloud_old_
protected

subscriber for a pointcloud (old format)

Definition at line 120 of file octree_pa_node.h.

ros::Subscriber cOctreePaNode::sub_laser_
protected

subscriber for a laserscan

Definition at line 126 of file octree_pa_node.h.

tf::TransformListener cOctreePaNode::tf_listener_
protected

transformation of different frames

Definition at line 110 of file octree_pa_node.h.


The documentation for this class was generated from the following files:


octomap_pa
Author(s):
autogenerated on Thu Jun 11 2020 03:38:50