Public Member Functions | Protected Member Functions | List of all members
cNearfieldMapDegradingPaNode Class Reference

#include <nearfield_map_degrading_pa_node.h>

Inheritance diagram for cNearfieldMapDegradingPaNode:
Inheritance graph
[legend]

Public Member Functions

 cNearfieldMapDegradingPaNode ()
 default constructor More...
 
 ~cNearfieldMapDegradingPaNode ()
 default destructor More...
 
- Public Member Functions inherited from cNearfieldMapBasePaNode< cOctreeStampedPaRos >
void changeSettings (void)
 
bool checkTF (const std_msgs::Header &header, tf::StampedTransform &transform)
 
 cNearfieldMapBasePaNode ()
 default constructor More...
 
bool getNearfield (sensor_msgs::PointCloud2Ptr &msg)
 function for retrieving requested nearfield map as pointcloud More...
 
void publish (void)
 function for publishing all topics (nearfield map and debugging) More...
 
 ~cNearfieldMapBasePaNode ()
 default destructor More...
 
- Public Member Functions inherited from cOctreeStampedPaRos
 cOctreeStampedPaRos (const double resolution)
 
void degradeOutdatedNodes (void)
 
ros::Time getLastInsertionTime (void) const
 
void setLastInsertionTime (const ros::Time &time)
 
cTimePa timeFromRos (const ros::Time &time) const
 
ros::Time timeToRos (const cTimePa &time) const
 
virtual ~cOctreeStampedPaRos ()
 
- Public Member Functions inherited from cOctreeBasePaRos< cOcTreeStampedPa >
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)
 
 cOctreeBasePaRos (double resolution)
 
bool getChildKey (const OctKey &current, const int current_level, OctKey &child, const int child_pos) const
 
octomap_msgs::OctomapPtr getOctomap (void) const
 
octomap_msgs::OctomapPtr getOctomapFull (void) const
 
sensor_msgs::PointCloud2Ptr getOctomapPcd (const int tree_depth=0, const bool expand=false) const
 
sensor_msgs::PointCloud2Ptr getOctomapPcdFree (const int tree_depth=0, const bool expand=false) const
 
ros::Time getOutputTime (void) const
 
bool getParentKey (const OctKey &current, const int current_level, OctKey &parent) const
 
void keyToPoint (const OctKey &key, double &x, double &y, double &z) const
 
geometry_msgs::PointPtr keyToPoint (const OctKey &key) const
 
OctKey pointToKey (const geometry_msgs::Point &point) const
 
bool readFull (const std::string &filename)
 
void setOutputTime (const ros::Time &time)
 
bool updateTime (const ros::Time &time)
 
virtual ~cOctreeBasePaRos ()
 
- Public Member Functions inherited from cOcTreeStampedPa
 cOcTreeStampedPa (double resolution)
 
cOcTreeStampedPacreate () const
 
virtual std::string getTreeType () const
 
virtual ~cOcTreeStampedPa (void)
 
- Public Member Functions inherited from cOcTreeStampedBasePa< octomap::OccupancyOcTreeBase, octomap::OcTreeNode >
 cOcTreeStampedBasePa (double resolution)
 
cOcTreeStampedBasePa< octomap::OccupancyOcTreeBase, octomap::OcTreeNode > * create () const
 
void degradeOutdatedNodes (const cTimePa timediff)
 
const cTimePagetTimestamp (void) const
 
void setTimestamp (const cTimePa timestamp)
 
virtual void updateNodeLogOdds (NodeTypeFull *node, const float &update) const
 
virtual ~cOcTreeStampedBasePa (void)
 

Protected Member Functions

void addPcdCameraCallbackSub (const sensor_msgs::PointCloud2ConstPtr &msg)
 callback function for receiving a depth images from camera More...
 
void addPcdLaserFullCallbackSub (const sensor_msgs::PointCloud2ConstPtr &msg)
 callback function for single laserscans More...
 
void addPcdLaserScanCallbackSub (const sensor_msgs::PointCloud2ConstPtr &msg)
 callback function for receiving a laserscan More...
 
bool getSizeCallbackSrv (nearfield_map::NearfieldMapGetSize::Request &req, nearfield_map::NearfieldMapGetSize::Response &res)
 service for receiving the size of the octomap More...
 
- Protected Member Functions inherited from cNearfieldMapBasePaNode< cOctreeStampedPaRos >
bool changeSettingsCallbackSrv (nearfield_map::NearfieldMapChangeSettings::Request &req, nearfield_map::NearfieldMapChangeSettings::Response &res)
 
bool clearCallbackSrv (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
 
void clearCallbackSub (const std_msgs::EmptyConstPtr &msg)
 
bool getSizeCallbackSrv (nearfield_map::NearfieldMapGetSize::Request &req, nearfield_map::NearfieldMapGetSize::Response &res)
 
bool loadCallbackSrv (nearfield_map::NearfieldMapFileName::Request &req, nearfield_map::NearfieldMapFileName::Response &res)
 
bool requestCallbackSrv (nearfield_map::NearfieldMapRequest::Request &req, nearfield_map::NearfieldMapRequest::Response &res)
 
bool saveCallbackSrv (nearfield_map::NearfieldMapFileName::Request &req, nearfield_map::NearfieldMapFileName::Response &res)
 
bool sendCallbackSrv (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
 
- Protected Member Functions inherited from cOctreeStampedPaRos
void checkDegrading (void)
 
- Protected Member Functions inherited from cOctreeBasePaRos< cOcTreeStampedPa >
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
 
void getOctomapPcdSub (const OctKey &key, const int current_level, const int min_level, PclPointCloud &cloud) const
 
void getParentKeySimple (const OctKey &current, const int current_level, OctKey &parent) const
 

Additional Inherited Members

- Public Types inherited from cNearfieldMapBasePaNode< cOctreeStampedPaRos >
typedef cOctreeStampedPaRos MapTypeBase
 
typedef cNearfieldMapBasePaNode< cOctreeStampedPaRosMapTypeFull
 
- Public Types inherited from cOctreeStampedPaRos
typedef cOctreeBasePaRos< cOcTreeStampedPaTreeTypeBase
 
- Public Types inherited from cOctreeBasePaRos< cOcTreeStampedPa >
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 cOcTreeStampedPa TreeTypeBase
 
typedef cOctreeBasePaRos< cOcTreeStampedPaTreeTypeFull
 
- Public Types inherited from cOcTreeStampedPa
typedef octomap::OcTreeNode NodeTypeBase
 
typedef cNodeStampedBasePa< NodeTypeBaseNodeTypeFull
 
typedef cOcTreeStampedBasePa< octomap::OccupancyOcTreeBase, NodeTypeBaseTreeTypeBase
 
- Public Types inherited from cOcTreeStampedBasePa< octomap::OccupancyOcTreeBase, octomap::OcTreeNode >
typedef octomap::OcTreeNode NodeTypeBase
 
typedef cNodeStampedBasePa< octomap::OcTreeNodeNodeTypeFull
 
typedef octomap::OccupancyOcTreeBase< NodeTypeFullTreeTypeBase
 
- Public Attributes inherited from cOctreeStampedPaRos
cOctreeStampedPaRosParameter rosparams_
 
- Public Attributes inherited from cOctreeBasePaRos< cOcTreeStampedPa >
cOctreeBasePaRosParameter rosparams_base_
 
- Protected Attributes inherited from cNearfieldMapBasePaNode< cOctreeStampedPaRos >
int count_camera_
 number of inserted depth images from camera (pointclouds) More...
 
int count_laser_full_
 number of inserted full laserscans (pointclouds) More...
 
int count_laser_scan_
 number of inserted single laserscans More...
 
ros::NodeHandle nh_
 node handler for topic subscription and advertising More...
 
cNearfieldMapPaNodeParameter nodeparams_
 parameters More...
 
cPcdFilterPaRos output_filter_
 
cPcdFilterPaRosThrottle output_throttle_
 
cAddCloudParameter params_addcloud_camera_
 parameter for insertion of depth images from camera More...
 
cAddCloudParameter params_addcloud_laser_full_
 parameter for insertion of full laserscans More...
 
cAddCloudParameter params_addcloud_laser_scan_
 parameter for insertion of single laserscans 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_nearfield_
 puplisher for requested nearfield map (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_change_settings_
 service for changing parameters of the nearfield map 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_request_
 service for requesting a nearfield map (pointcloud) via this service More...
 
ros::ServiceServer srv_save_
 service for saving the octomap More...
 
ros::ServiceServer srv_send_
 service for requesting a nearfield map (pointcloud) via output topic More...
 
ros::Subscriber sub_camera_
 subscriber for depth images from camera More...
 
ros::Subscriber sub_clear_
 subscriber for clearing the octomap More...
 
ros::Subscriber sub_laser_full_
 subscriber for single laserscans More...
 
ros::Subscriber sub_laser_scan_
 subscriber for a laserscan More...
 
tf::TransformListener tf_listener_
 transformation of different frames More...
 
- Protected Attributes inherited from cOctreeStampedPaRos
ros::Time last_degrading_time_
 
- Protected Attributes inherited from cOctreeBasePaRos< cOcTreeStampedPa >
ros::Time current_output_time_
 
ros::Time last_insertion_time_
 
- Protected Attributes inherited from cOcTreeStampedBasePa< octomap::OccupancyOcTreeBase, octomap::OcTreeNode >
cTimePa current_timestamp
 
- Static Protected Attributes inherited from cOcTreeStampedPa
static StaticMemberInitializer StaticMemberInit
 

Detailed Description

Definition at line 66 of file nearfield_map_degrading_pa_node.h.

Constructor & Destructor Documentation

cNearfieldMapDegradingPaNode::cNearfieldMapDegradingPaNode ( )

default constructor

Definition at line 67 of file nearfield_map_degrading_pa_node.cpp.

cNearfieldMapDegradingPaNode::~cNearfieldMapDegradingPaNode ( )

default destructor

Definition at line 96 of file nearfield_map_degrading_pa_node.cpp.

Member Function Documentation

void cNearfieldMapDegradingPaNode::addPcdCameraCallbackSub ( const sensor_msgs::PointCloud2ConstPtr &  msg)
protected

callback function for receiving a depth images from camera

Definition at line 101 of file nearfield_map_degrading_pa_node.cpp.

void cNearfieldMapDegradingPaNode::addPcdLaserFullCallbackSub ( const sensor_msgs::PointCloud2ConstPtr &  msg)
protected

callback function for single laserscans

Definition at line 139 of file nearfield_map_degrading_pa_node.cpp.

void cNearfieldMapDegradingPaNode::addPcdLaserScanCallbackSub ( const sensor_msgs::PointCloud2ConstPtr &  msg)
protected

callback function for receiving a laserscan

Definition at line 120 of file nearfield_map_degrading_pa_node.cpp.

bool cNearfieldMapDegradingPaNode::getSizeCallbackSrv ( nearfield_map::NearfieldMapGetSize::Request &  req,
nearfield_map::NearfieldMapGetSize::Response &  res 
)
protected

service for receiving the size of the octomap


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


nearfield_map
Author(s):
autogenerated on Sat Feb 27 2021 03:09:46