56 int main(
int argc,
char **argv) {
58 ros::init(argc, argv,
"nearfield_map_pa_node");
98 const sensor_msgs::PointCloud2ConstPtr &msg) {
106 if (!
checkTF(msg->header, transform)) {
return;}
116 const sensor_msgs::PointCloud2ConstPtr &msg) {
124 if (!
checkTF(msg->header, transform)) {
return;}
134 const sensor_msgs::PointCloud2ConstPtr &msg) {
142 if (!
checkTF(msg->header, transform)) {
return;}
ros::NodeHandle nh_
node handler for topic subscription and advertising
ros::Subscriber sub_laser_scan_
subscriber for a laserscan
std::string topic_in_camera_
cNearfieldMapPaNodeParameter nodeparams_
parameters
int count_camera_
number of inserted depth images from camera (pointclouds)
ros::Subscriber sub_laser_full_
subscriber for single laserscans
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool updateTime(const ros::Time &time)
tf::TransformListener tf_listener_
transformation of different frames
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool checkTF(const std_msgs::Header &header, tf::StampedTransform &transform)
cAddCloudParameter params_addcloud_laser_scan_
parameter for insertion of single laserscans
int count_laser_full_
number of inserted full laserscans (pointclouds)
cAddCloudParameter params_addcloud_camera_
parameter for insertion of depth images from camera
ROSCPP_DECL void spin(Spinner &spinner)
void addPcdCameraCallbackSub(const sensor_msgs::PointCloud2ConstPtr &msg)
callback function for receiving a depth images from camera
void addPcdLaserScanCallbackSub(const sensor_msgs::PointCloud2ConstPtr &msg)
callback function for receiving a laserscan
std::string topic_in_laser_scan_
name of the topic for subscribing single laserscans ("in_laser_scan")
bool addCloud(const sensor_msgs::PointCloud2ConstPtr &cloud, const cAddCloudParameter ¶ms, const tf::Transform transform=tf::Transform::getIdentity())
int count_laser_scan_
number of inserted single laserscans
std::string topic_in_laser_full_
name of the topic for subscribing full laserscans ("in_laser_full")
cAddCloudParameter params_addcloud_laser_full_
parameter for insertion of full laserscans
int main(int argc, char **argv)
~cNearfieldMapPaNode()
default destructor
void publish(void)
function for publishing all topics (nearfield map and debugging)
void addPcdLaserFullCallbackSub(const sensor_msgs::PointCloud2ConstPtr &msg)
callback function for single laserscans
cNearfieldMapPaNode()
default constructor
ros::Subscriber sub_camera_
subscriber for depth images from camera