nearfield_map_pa_node.cpp
Go to the documentation of this file.
1 /******************************************************************************
2 * *
3 * nearfield_map_pa_node.cpp *
4 * ========================= *
5 * *
6 *******************************************************************************
7 * *
8 * Repository: *
9 * https://github.com/TUC-ProAut/ros_nearfield_map *
10 * *
11 * Chair of Automation Technology, Technische Universität Chemnitz *
12 * https://www.tu-chemnitz.de/etit/proaut *
13 * *
14 * Author: *
15 * Peter Weissig *
16 * *
17 *******************************************************************************
18 * *
19 * New BSD License *
20 * *
21 * Copyright (c) 2015-2021 TU Chemnitz *
22 * All rights reserved. *
23 * *
24 * Redistribution and use in source and binary forms, with or without *
25 * modification, are permitted provided that the following conditions are met: *
26 * * Redistributions of source code must retain the above copyright notice, *
27 * this list of conditions and the following disclaimer. *
28 * * Redistributions in binary form must reproduce the above copyright *
29 * notice, this list of conditions and the following disclaimer in the *
30 * documentation and/or other materials provided with the distribution. *
31 * * Neither the name of the copyright holder nor the names of its *
32 * contributors may be used to endorse or promote products derived from *
33 * this software without specific prior written permission. *
34 * *
35 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS *
36 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED *
37 * TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR *
38 * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR *
39 * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, *
40 * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, *
41 * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; *
42 * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, *
43 * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR *
44 * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF *
45 * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *
46 * *
47 ******************************************************************************/
48 
49 // local headers
50 #include "nearfield_map_pa_node.h"
51 
52 // ros headers
53 #include <parameter_pa/parameter_pa_ros.h>
54 
55 // standard headers
56 #include <string>
57 
58 //**************************[main]*********************************************
59 int main(int argc, char **argv) {
60 
61  ros::init(argc, argv, "nearfield_map_pa_node");
62  cNearfieldMapPaNode octomap;
63 
64  ros::spin();
65 
66  return 0;
67 }
68 
69 //**************************[cNearfieldMapPaNode]******************************
71 
72  cParameterPaRos paramloader;
73 
74  // Subscriber for depth images from camera
75  if (nodeparams_.topic_in_camera_ != "") {
76  sub_camera_ = nh_.subscribe<sensor_msgs::PointCloud2>(
79  }
80  // Subscriber for single laserscans
82  sub_laser_scan_ = nh_.subscribe<sensor_msgs::PointCloud2>(
85  }
86  // Subscriber for full laserscans
88  sub_laser_full_ = nh_.subscribe<sensor_msgs::PointCloud2>(
91  }
92 }
93 
94 //**************************[~cNearfieldMapPaNode]*****************************
96 
97 }
98 
99 //**************************[addPcdCameraCallbackSub]**************************
101  const sensor_msgs::PointCloud2ConstPtr &msg) {
102 
103  if (!updateTime(msg->header.stamp)) {
105  return;
106  }
107 
108  tf::StampedTransform transform;
109  if (! checkTF(msg->header, transform)) { return;}
110 
111  if (addCloud(*msg, params_addcloud_camera_, transform)) {
112  count_camera_++;
113  publish();
114  }
115 }
116 
117 //**************************[addPcdLaserScanCallbackSub]***********************
119  const sensor_msgs::PointCloud2ConstPtr &msg) {
120 
121  if (!updateTime(msg->header.stamp)) {
123  return;
124  }
125 
126  tf::StampedTransform transform;
127  if (! checkTF(msg->header, transform)) { return;}
128 
129  if (addCloud(*msg, params_addcloud_laser_scan_, transform)) {
131  publish();
132  }
133 }
134 
135 //**************************[addPcdLaserFullCallbackSub]***********************
137  const sensor_msgs::PointCloud2ConstPtr &msg) {
138 
139  if (!updateTime(msg->header.stamp)) {
141  return;
142  }
143 
144  tf::StampedTransform transform;
145  if (! checkTF(msg->header, transform)) { return;}
146 
147  if (addCloud(*msg, params_addcloud_laser_full_, transform)) {
149  publish();
150  }
151 }
cNearfieldMapPaNode
Definition: nearfield_map_pa_node.h:64
cNearfieldMapBasePaNode< cOctreePaRos >::sub_laser_full_
ros::Subscriber sub_laser_full_
subscriber for single laserscans
Definition: nearfield_map_base_pa_node.h:194
cNearfieldMapBasePaNode< cOctreePaRos >::tf_listener_
tf::TransformListener tf_listener_
transformation of different frames
Definition: nearfield_map_base_pa_node.h:181
cNearfieldMapPaNodeParameter::topic_in_laser_scan_
std::string topic_in_laser_scan_
name of the topic for subscribing single laserscans ("in_laser_scan")
Definition: nearfield_map_pa_node_parameter.h:110
cNearfieldMapBasePaNode< cOctreePaRos >::sub_camera_
ros::Subscriber sub_camera_
subscriber for depth images from camera
Definition: nearfield_map_base_pa_node.h:190
cNearfieldMapPaNode::addPcdLaserScanCallbackSub
void addPcdLaserScanCallbackSub(const sensor_msgs::PointCloud2ConstPtr &msg)
callback function for receiving a laserscan
Definition: nearfield_map_pa_node.cpp:118
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
cNearfieldMapBasePaNode< cOctreePaRos >::checkTF
bool checkTF(const std_msgs::Header &header, tf::StampedTransform &transform)
main
int main(int argc, char **argv)
Definition: nearfield_map_pa_node.cpp:59
cNearfieldMapBasePaNode< cOctreePaRos >::params_addcloud_camera_
cAddCloudParameter params_addcloud_camera_
parameter for insertion of depth images from camera
Definition: nearfield_map_base_pa_node.h:163
cNearfieldMapBasePaNode< cOctreePaRos >::count_camera_
int count_camera_
number of inserted depth images from camera (pointclouds)
Definition: nearfield_map_base_pa_node.h:171
cNearfieldMapPaNodeParameter::topic_in_camera_
std::string topic_in_camera_
Definition: nearfield_map_pa_node_parameter.h:108
tf::StampedTransform
cNearfieldMapPaNode::~cNearfieldMapPaNode
~cNearfieldMapPaNode()
default destructor
Definition: nearfield_map_pa_node.cpp:95
cNearfieldMapBasePaNode< cOctreePaRos >::params_addcloud_laser_scan_
cAddCloudParameter params_addcloud_laser_scan_
parameter for insertion of single laserscans
Definition: nearfield_map_base_pa_node.h:165
cNearfieldMapBasePaNode< cOctreePaRos >::count_laser_full_
int count_laser_full_
number of inserted full laserscans (pointclouds)
Definition: nearfield_map_base_pa_node.h:175
cNearfieldMapBasePaNode< cOctreePaRos >::count_laser_scan_
int count_laser_scan_
number of inserted single laserscans
Definition: nearfield_map_base_pa_node.h:173
cNearfieldMapPaNode::cNearfieldMapPaNode
cNearfieldMapPaNode()
default constructor
Definition: nearfield_map_pa_node.cpp:70
cNearfieldMapBasePaNode< cOctreePaRos >::params_addcloud_laser_full_
cAddCloudParameter params_addcloud_laser_full_
parameter for insertion of full laserscans
Definition: nearfield_map_base_pa_node.h:167
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
cNearfieldMapPaNode::addPcdCameraCallbackSub
void addPcdCameraCallbackSub(const sensor_msgs::PointCloud2ConstPtr &msg)
callback function for receiving a depth images from camera
Definition: nearfield_map_pa_node.cpp:100
nearfield_map_pa_node.h
cNearfieldMapBasePaNode< cOctreePaRos >::publish
void publish(void)
function for publishing all topics (nearfield map and debugging)
tf::Transformer::clear
void clear()
cNearfieldMapPaNode::addPcdLaserFullCallbackSub
void addPcdLaserFullCallbackSub(const sensor_msgs::PointCloud2ConstPtr &msg)
callback function for single laserscans
Definition: nearfield_map_pa_node.cpp:136
ros::spin
ROSCPP_DECL void spin()
cNearfieldMapPaNodeParameter::topic_in_laser_full_
std::string topic_in_laser_full_
name of the topic for subscribing full laserscans ("in_laser_full")
Definition: nearfield_map_pa_node_parameter.h:112
cNearfieldMapBasePaNode< cOctreePaRos >::nh_
ros::NodeHandle nh_
node handler for topic subscription and advertising
Definition: nearfield_map_base_pa_node.h:178
cNearfieldMapBasePaNode< cOctreePaRos >::nodeparams_
cNearfieldMapPaNodeParameter nodeparams_
parameters
Definition: nearfield_map_base_pa_node.h:160
cNearfieldMapBasePaNode< cOctreePaRos >::sub_laser_scan_
ros::Subscriber sub_laser_scan_
subscriber for a laserscan
Definition: nearfield_map_base_pa_node.h:192


nearfield_map
Author(s):
autogenerated on Wed Mar 2 2022 00:42:09