#include <nearfield_map_base_pa_node.h>
Public Types | |
typedef NEARFIELDMAP | MapTypeBase |
typedef cNearfieldMapBasePaNode< NEARFIELDMAP > | MapTypeFull |
Public Member Functions | |
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... | |
Protected Member Functions | |
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 Attributes | |
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... | |
Definition at line 83 of file nearfield_map_base_pa_node.h.
typedef NEARFIELDMAP cNearfieldMapBasePaNode< NEARFIELDMAP >::MapTypeBase |
Definition at line 86 of file nearfield_map_base_pa_node.h.
typedef cNearfieldMapBasePaNode<NEARFIELDMAP> cNearfieldMapBasePaNode< NEARFIELDMAP >::MapTypeFull |
Definition at line 87 of file nearfield_map_base_pa_node.h.
cNearfieldMapBasePaNode< NEARFIELDMAP >::cNearfieldMapBasePaNode | ( | ) |
default constructor
cNearfieldMapBasePaNode< NEARFIELDMAP >::~cNearfieldMapBasePaNode | ( | ) |
default destructor
void cNearfieldMapBasePaNode< NEARFIELDMAP >::changeSettings | ( | void | ) |
|
protected |
bool cNearfieldMapBasePaNode< NEARFIELDMAP >::checkTF | ( | const std_msgs::Header & | header, |
tf::StampedTransform & | transform | ||
) |
checking if transform from header to octomap frame (output_frame_) is possible and returns fransform
|
protected |
|
protected |
bool cNearfieldMapBasePaNode< NEARFIELDMAP >::getNearfield | ( | sensor_msgs::PointCloud2Ptr & | msg | ) |
function for retrieving requested nearfield map as pointcloud
|
protected |
|
protected |
void cNearfieldMapBasePaNode< NEARFIELDMAP >::publish | ( | void | ) |
function for publishing all topics (nearfield map and debugging)
|
protected |
|
protected |
|
protected |
|
protected |
number of inserted depth images from camera (pointclouds)
Definition at line 122 of file nearfield_map_base_pa_node.h.
|
protected |
number of inserted full laserscans (pointclouds)
Definition at line 126 of file nearfield_map_base_pa_node.h.
|
protected |
number of inserted single laserscans
Definition at line 124 of file nearfield_map_base_pa_node.h.
|
protected |
node handler for topic subscription and advertising
Definition at line 129 of file nearfield_map_base_pa_node.h.
|
protected |
parameters
Definition at line 111 of file nearfield_map_base_pa_node.h.
|
protected |
Definition at line 138 of file nearfield_map_base_pa_node.h.
|
protected |
Definition at line 135 of file nearfield_map_base_pa_node.h.
|
protected |
parameter for insertion of depth images from camera
Definition at line 114 of file nearfield_map_base_pa_node.h.
|
protected |
parameter for insertion of full laserscans
Definition at line 118 of file nearfield_map_base_pa_node.h.
|
protected |
parameter for insertion of single laserscans
Definition at line 116 of file nearfield_map_base_pa_node.h.
|
protected |
puplisher for free voxels as pointcloud
Definition at line 152 of file nearfield_map_base_pa_node.h.
|
protected |
puplisher for occupied voxels as pointcloud
Definition at line 154 of file nearfield_map_base_pa_node.h.
|
protected |
puplisher for requested nearfield map (pointcloud)
Definition at line 156 of file nearfield_map_base_pa_node.h.
|
protected |
puplisher for the octomap (binary data)
Definition at line 148 of file nearfield_map_base_pa_node.h.
|
protected |
puplisher for the octomap (full data)
Definition at line 150 of file nearfield_map_base_pa_node.h.
|
protected |
service for changing parameters of the nearfield map
Definition at line 196 of file nearfield_map_base_pa_node.h.
|
protected |
service for clearing the octomap
Definition at line 164 of file nearfield_map_base_pa_node.h.
|
protected |
service for receiving the size of the octomap
Definition at line 169 of file nearfield_map_base_pa_node.h.
|
protected |
service for loading a octomap
Definition at line 180 of file nearfield_map_base_pa_node.h.
|
protected |
service for requesting a nearfield map (pointcloud) via this service
Definition at line 190 of file nearfield_map_base_pa_node.h.
|
protected |
service for saving the octomap
Definition at line 175 of file nearfield_map_base_pa_node.h.
|
protected |
service for requesting a nearfield map (pointcloud) via output topic
Definition at line 186 of file nearfield_map_base_pa_node.h.
|
protected |
subscriber for depth images from camera
Definition at line 141 of file nearfield_map_base_pa_node.h.
|
protected |
subscriber for clearing the octomap
Definition at line 160 of file nearfield_map_base_pa_node.h.
|
protected |
subscriber for single laserscans
Definition at line 145 of file nearfield_map_base_pa_node.h.
|
protected |
subscriber for a laserscan
Definition at line 143 of file nearfield_map_base_pa_node.h.
|
protected |
transformation of different frames
Definition at line 132 of file nearfield_map_base_pa_node.h.