nearfield_map_pa_node_parameter.cpp
Go to the documentation of this file.
1 /******************************************************************************
2 * *
3 * nearfield_map_pa_node_parameter.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 #include <string>
53 
54 //**************************[cNearfieldMapPaNodeParameter]*********************
56  // topics
57  topic_in_camera_ = "~/in_camera" ;
58  topic_in_laser_scan_ = "~/in_laser_scan";
59  topic_in_laser_full_ = "~/in_laser_full";
60 
61  topic_out_nearfield_ = "~/out_nearfield";
62 
63  topic_out_octomap_ = "~/out_octomap" ;
64  topic_out_octomap_full_ = "~/out_octomap_full";
65 
66  topic_out_cloud_free_ = "~/out_cloud_free" ;
67  topic_out_cloud_occupied_ = "~/out_cloud_occupied" ;
68 
69  // services
70  topic_in_clear_ = "~/in_clear" ;
71 
72  // bounding box for output
73  filter_frame_ = "base_footprint";
74  filter_dx_ = 5;
75  filter_dy_ = 5;
76  filter_dz_ = 3;
77 
78 }
cNearfieldMapPaNodeParameter::topic_in_clear_
std::string topic_in_clear_
name of the topic for clearing the octomap ("~/in_clear")
Definition: nearfield_map_pa_node_parameter.h:132
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
cNearfieldMapPaNodeParameter::filter_dz_
double filter_dz_
flag size of bounding box in z-direction
Definition: nearfield_map_pa_node_parameter.h:141
cNearfieldMapPaNodeParameter::topic_out_octomap_full_
std::string topic_out_octomap_full_
name of the topic for publishing the octomap ("~/out_octomap_full")
Definition: nearfield_map_pa_node_parameter.h:121
cNearfieldMapPaNodeParameter::topic_in_camera_
std::string topic_in_camera_
Definition: nearfield_map_pa_node_parameter.h:108
cNearfieldMapPaNodeParameter::filter_dy_
double filter_dy_
flag size of bounding box in y-direction
Definition: nearfield_map_pa_node_parameter.h:139
cNearfieldMapPaNodeParameter::topic_out_nearfield_
std::string topic_out_nearfield_
Definition: nearfield_map_pa_node_parameter.h:116
cNearfieldMapPaNodeParameter::cNearfieldMapPaNodeParameter
cNearfieldMapPaNodeParameter(void)
Definition: nearfield_map_pa_node_parameter.cpp:55
nearfield_map_pa_node_parameter.h
cNearfieldMapPaNodeParameter::topic_out_cloud_free_
std::string topic_out_cloud_free_
Definition: nearfield_map_pa_node_parameter.h:125
cNearfieldMapPaNodeParameter::topic_out_cloud_occupied_
std::string topic_out_cloud_occupied_
Definition: nearfield_map_pa_node_parameter.h:128
cNearfieldMapPaNodeParameter::topic_out_octomap_
std::string topic_out_octomap_
name of the topic for publishing the octomap ("~/out_octomap")
Definition: nearfield_map_pa_node_parameter.h:119
cNearfieldMapPaNodeParameter::filter_dx_
double filter_dx_
flag size of bounding box in x-direction
Definition: nearfield_map_pa_node_parameter.h:137
cNearfieldMapPaNodeParameter::filter_frame_
std::string filter_frame_
frame id expressing the center and orientation of bounding box
Definition: nearfield_map_pa_node_parameter.h:135
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


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