nearfield_map_degrading_native_node.cpp
Go to the documentation of this file.
1 /******************************************************************************
2 * *
3 * nearfield_map_degrading_native_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
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_native_node");
63 
64  ros::spin();
65 
66  return 0;
67 }
68 
69 //**************************[cNearfieldMapDegradingNativeNode]*****************
71 
72  cParameterPaRos paramloader;
73  paramloader.load("~/degrading_time" , rosparams_.degrading_time_);
74  paramloader.load("~/auto_degrading" , rosparams_.auto_degrading_);
75  paramloader.load("~/auto_degrading_intervall",
76  rosparams_.auto_degrading_intervall_);
77 
78  // Subscriber for depth images from camera
79  if (nodeparams_.topic_in_camera_ != "") {
80  sub_camera_ = nh_.subscribe<sensor_msgs::PointCloud2>(
83  }
84  // Subscriber for single laserscans
86  sub_laser_scan_ = nh_.subscribe<sensor_msgs::PointCloud2>(
89  }
90  // Subscriber for full laserscans
92  sub_laser_full_ = nh_.subscribe<sensor_msgs::PointCloud2>(
95  }
96 }
97 
98 //**************************[~cNearfieldMapDegradingNativeNode]****************
100 
101 }
102 
103 //**************************[addPcdCameraCallbackSub]**************************
105  const sensor_msgs::PointCloud2ConstPtr &msg) {
106 
107  if (!updateTime(msg->header.stamp)) {
109  return;
110  }
111 
112  tf::StampedTransform transform;
113  if (! checkTF(msg->header, transform)) { return;}
114 
115  if (addCloud(*msg, params_addcloud_camera_, transform)) {
116  count_camera_++;
117  checkDegrading();
118  publish();
119  }
120 }
121 
122 //**************************[addPcdLaserScanCallbackSub]***********************
124  const sensor_msgs::PointCloud2ConstPtr &msg) {
125 
126  if (!updateTime(msg->header.stamp)) {
128  return;
129  }
130 
131  tf::StampedTransform transform;
132  if (! checkTF(msg->header, transform)) { return;}
133 
134  if (addCloud(*msg, params_addcloud_laser_scan_, transform)) {
136  checkDegrading();
137  publish();
138  }
139 }
140 
141 //**************************[addPcdLaserFullCallbackSub]***********************
143  const sensor_msgs::PointCloud2ConstPtr &msg) {
144 
145  if (!updateTime(msg->header.stamp)) {
147  return;
148  }
149 
150  tf::StampedTransform transform;
151  if (! checkTF(msg->header, transform)) { return;}
152 
153  if (addCloud(*msg, params_addcloud_laser_full_, transform)) {
155  checkDegrading();
156  publish();
157  }
158 }
cNearfieldMapBasePaNode< cOctreeStampedNativeRos >::sub_laser_full_
ros::Subscriber sub_laser_full_
subscriber for single laserscans
Definition: nearfield_map_base_pa_node.h:194
cNearfieldMapBasePaNode< cOctreeStampedNativeRos >::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< cOctreeStampedNativeRos >::sub_camera_
ros::Subscriber sub_camera_
subscriber for depth images from camera
Definition: nearfield_map_base_pa_node.h:190
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
cNearfieldMapBasePaNode< cOctreeStampedNativeRos >::checkTF
bool checkTF(const std_msgs::Header &header, tf::StampedTransform &transform)
cNearfieldMapDegradingNativeNode::addPcdLaserFullCallbackSub
void addPcdLaserFullCallbackSub(const sensor_msgs::PointCloud2ConstPtr &msg)
callback function for single laserscans
Definition: nearfield_map_degrading_native_node.cpp:142
cNearfieldMapBasePaNode< cOctreeStampedNativeRos >::params_addcloud_camera_
cAddCloudParameter params_addcloud_camera_
parameter for insertion of depth images from camera
Definition: nearfield_map_base_pa_node.h:163
cNearfieldMapDegradingNativeNode::addPcdCameraCallbackSub
void addPcdCameraCallbackSub(const sensor_msgs::PointCloud2ConstPtr &msg)
callback function for receiving a depth images from camera
Definition: nearfield_map_degrading_native_node.cpp:104
cNearfieldMapBasePaNode< cOctreeStampedNativeRos >::count_camera_
int count_camera_
number of inserted depth images from camera (pointclouds)
Definition: nearfield_map_base_pa_node.h:171
nearfield_map_degrading_native_node.h
cNearfieldMapPaNodeParameter::topic_in_camera_
std::string topic_in_camera_
Definition: nearfield_map_pa_node_parameter.h:108
tf::StampedTransform
main
int main(int argc, char **argv)
Definition: nearfield_map_degrading_native_node.cpp:59
cNearfieldMapDegradingNativeNode::~cNearfieldMapDegradingNativeNode
~cNearfieldMapDegradingNativeNode()
default destructor
Definition: nearfield_map_degrading_native_node.cpp:99
cNearfieldMapBasePaNode< cOctreeStampedNativeRos >::params_addcloud_laser_scan_
cAddCloudParameter params_addcloud_laser_scan_
parameter for insertion of single laserscans
Definition: nearfield_map_base_pa_node.h:165
cNearfieldMapBasePaNode< cOctreeStampedNativeRos >::count_laser_full_
int count_laser_full_
number of inserted full laserscans (pointclouds)
Definition: nearfield_map_base_pa_node.h:175
cNearfieldMapBasePaNode< cOctreeStampedNativeRos >::count_laser_scan_
int count_laser_scan_
number of inserted single laserscans
Definition: nearfield_map_base_pa_node.h:173
cNearfieldMapBasePaNode< cOctreeStampedNativeRos >::params_addcloud_laser_full_
cAddCloudParameter params_addcloud_laser_full_
parameter for insertion of full laserscans
Definition: nearfield_map_base_pa_node.h:167
cNearfieldMapDegradingNativeNode
Definition: nearfield_map_degrading_native_node.h:64
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())
cNearfieldMapDegradingNativeNode::cNearfieldMapDegradingNativeNode
cNearfieldMapDegradingNativeNode()
default constructor
Definition: nearfield_map_degrading_native_node.cpp:70
cNearfieldMapBasePaNode< cOctreeStampedNativeRos >::publish
void publish(void)
function for publishing all topics (nearfield map and debugging)
tf::Transformer::clear
void clear()
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< cOctreeStampedNativeRos >::nh_
ros::NodeHandle nh_
node handler for topic subscription and advertising
Definition: nearfield_map_base_pa_node.h:178
cNearfieldMapDegradingNativeNode::addPcdLaserScanCallbackSub
void addPcdLaserScanCallbackSub(const sensor_msgs::PointCloud2ConstPtr &msg)
callback function for receiving a laserscan
Definition: nearfield_map_degrading_native_node.cpp:123
cNearfieldMapBasePaNode< cOctreeStampedNativeRos >::nodeparams_
cNearfieldMapPaNodeParameter nodeparams_
parameters
Definition: nearfield_map_base_pa_node.h:160
cNearfieldMapBasePaNode< cOctreeStampedNativeRos >::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