nearfield_map_pa_node.h
Go to the documentation of this file.
1 /******************************************************************************
2 * *
3 * nearfield_map_pa_node.h *
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 #ifndef __NEARFIELD_MAP_PA_NODE_H
50 #define __NEARFIELD_MAP_PA_NODE_H
51 
52 // local headers
54 
55 #include "nearfield_map/NearfieldMapGetSize.h"
56 
57 // ros headers
58 #include <ros/ros.h>
59 
60 #include <octomap_pa/octree_pa_ros.h>
61 #include <octomap_pa/addcloud_parameter.h>
62 
63 //**************************[cNearfieldMapPaNode]******************************
64 class cNearfieldMapPaNode : public cNearfieldMapBasePaNode<cOctreePaRos> {
65  public:
68 
71 
72  protected:
74  cAddCloudParameter params_octomap_camera_;
76  cAddCloudParameter params_octomap_laser_scan_;
78  cAddCloudParameter params_octomap_laser_full_;
79 
82  const sensor_msgs::PointCloud2ConstPtr &msg);
85  const sensor_msgs::PointCloud2ConstPtr &msg);
88  const sensor_msgs::PointCloud2ConstPtr &msg);
89 
91  bool getSizeCallbackSrv(
92  nearfield_map::NearfieldMapGetSize::Request &req,
93  nearfield_map::NearfieldMapGetSize::Response &res);
94 };
95 
96 #endif // __NEARFIELD_MAP_PA_NODE_H
cNearfieldMapPaNode
Definition: nearfield_map_pa_node.h:64
nearfield_map_base_pa_node.h
cNearfieldMapPaNode::addPcdLaserScanCallbackSub
void addPcdLaserScanCallbackSub(const sensor_msgs::PointCloud2ConstPtr &msg)
callback function for receiving a laserscan
Definition: nearfield_map_pa_node.cpp:118
ros.h
cNearfieldMapPaNode::params_octomap_camera_
cAddCloudParameter params_octomap_camera_
parameter for insertion of depth images from camera (octomap)
Definition: nearfield_map_pa_node.h:120
cNearfieldMapBasePaNode
Definition: nearfield_map_base_pa_node.h:86
cNearfieldMapPaNode::~cNearfieldMapPaNode
~cNearfieldMapPaNode()
default destructor
Definition: nearfield_map_pa_node.cpp:95
cNearfieldMapPaNode::params_octomap_laser_scan_
cAddCloudParameter params_octomap_laser_scan_
parameter for insertion of single laserscans (octomap)
Definition: nearfield_map_pa_node.h:122
cNearfieldMapPaNode::cNearfieldMapPaNode
cNearfieldMapPaNode()
default constructor
Definition: nearfield_map_pa_node.cpp:70
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
cNearfieldMapPaNode::addPcdLaserFullCallbackSub
void addPcdLaserFullCallbackSub(const sensor_msgs::PointCloud2ConstPtr &msg)
callback function for single laserscans
Definition: nearfield_map_pa_node.cpp:136
cNearfieldMapPaNode::getSizeCallbackSrv
bool getSizeCallbackSrv(nearfield_map::NearfieldMapGetSize::Request &req, nearfield_map::NearfieldMapGetSize::Response &res)
service for receiving the size of the octomap
cNearfieldMapPaNode::params_octomap_laser_full_
cAddCloudParameter params_octomap_laser_full_
parameter for insertion of full laserscans (octomap)
Definition: nearfield_map_pa_node.h:124


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