ellipses_nodelet_parameters.cpp
Go to the documentation of this file.
1 /***************************************************************************
2  * Copyright (c) 2014 Markus Bader <markus.bader@tuwien.ac.at>
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  * 1. Redistributions of source code must retain the above copyright
8  * notice, this list of conditions and the following disclaimer.
9  * 2. Redistributions in binary form must reproduce the above copyright
10  * notice, this list of conditions and the following disclaimer in the
11  * documentation and/or other materials provided with the distribution.
12  * 3. All advertising materials mentioning features or use of this software
13  * must display the following acknowledgement:
14  * This product includes software developed by the TU-Wien.
15  * 4. Neither the name of the TU-Wien nor the
16  * names of its contributors may be used to endorse or promote products
17  * derived from this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY Markus Bader ''AS IS'' AND ANY
20  * EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
21  * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22  * DISCLAIMED. IN NO EVENT SHALL Markus Bader BE LIABLE FOR ANY
23  * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
24  * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
25  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
26  * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
27  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
28  * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
29  ***************************************************************************/
30 
31 #include "ellipses_nodelet.h"
33 
34 using namespace tuw;
35 
37  : Parameters()
38  , node("~")
39  , node_name(node.getNamespace())
41  , publishTF(TUW_ELLIPSES_NODE_PUBLISH_TF)
42  , publishMarker(TUW_ELLIPSES_NODE_PUBLISH_MARKER)
43  , publishFiducials(TUW_ELLIPSES_NODE_PUBLISH_FIDUCIALS)
45  , show_camera_image_waitkey(TUW_ELLIPSES_NODE_DEFAULT_SHOW_CAMERA_IMAGE_WAITKEY)
48  , tf_prefix(node_name)
49  {
50  node.getParam("debug_freeze", debug_freeze);
51  ROS_INFO("%s - debug_freeze: %s", node_name.c_str(), (debug_freeze ? "true" : "false"));
52  node.getParam("show_camera_image", show_camera_image);
53  ROS_INFO("%s - show_camera_image: %s", node_name.c_str(), (show_camera_image ? "true" : "false"));
54  node.getParam("show_camera_image_waitkey", show_camera_image_waitkey);
55  ROS_INFO("%s - show_camera_image_waitkey: %i", node_name.c_str(), show_camera_image_waitkey);
56  node.getParam("image_skip", image_skip);
57  ROS_INFO("%s - image_skip: %i", node_name.c_str(), image_skip);
58  node.param<std::string>("tf_prefix", tf_prefix, node_name);
59  ROS_INFO("%s: tf_prefix: %s", node_name.c_str(), tf_prefix.c_str());
60  node.getParam("skip_second_tf", skip_second_tf);
61  ROS_INFO("%s - skip_second_tf: %s", node_name.c_str(), (skip_second_tf ? "true" : "false"));
62 
65 
66 
67 }
68 
69 
70 void EllipsesDetectionNode::ParametersNode::callbackParameters (tuw_ellipses::EllipsesDetectionConfig &config, uint32_t level ) {
71  int kernal_sizes[] = {1, 3, 5, 7};
72  show_camera_image = config.show_camera_image;
73  show_camera_image_waitkey = config.show_camera_image_waitkey;
74  debug = config.debug;
75  distorted_input = config.distorted_input;
76  debug_freeze = config.debug_freeze;
77  image_skip = config.image_skip;
78  edge_detection = (EdgeDetection) config.edge_detection;
79  threshold_edge_detection1 = config.threshold_edge_detection1;
80  threshold_edge_detection2 = config.threshold_edge_detection2;
81  if(config.kernel_size_edge_detection > 7) kernel_size_edge_detection = 7;
82  else if(config.kernel_size_edge_detection < 3) kernel_size_edge_detection = 3;
83  else if(config.kernel_size_edge_detection % 2) kernel_size_edge_detection = config.kernel_size_edge_detection;
84  else kernel_size_edge_detection = config.kernel_size_edge_detection+1;
85  edge_linking = (EdgeLinking) config.edge_linking;
86  threshold_contour_min_points = config.threshold_contour_min_points;
87  threshold_polygon = config.threshold_polygon;
88  filter_convex = config.filter_convex;
89  ellipse_redefinement = config.ellipse_redefinement;
90  threshold_rotated_rect_ratio = config.threshold_rotated_rect_ratio;
91  filter_contour_mean = config.filter_contour_mean;
92  threshold_min_radius = config.threshold_min_radius;
93  threshold_max_radius = config.threshold_max_radius;
94  filter_rings = config.filter_rings;
95  threshold_ring_center = config.threshold_ring_center;
96  threshold_ring_ratio = config.threshold_ring_ratio;
97  pose_estimation = (PoseEstimation) config.pose_estimation;
98  circle_diameter = config.circle_diameter;
99  skip_second_tf = config.skip_second_tf;
100 
101 }
dynamic_reconfigure::Server< tuw_ellipses::EllipsesDetectionConfig > reconfigureServer_
#define TUW_ELLIPSES_NODE_DEFAULT_IMAGE_SKIP
dynamic_reconfigure::Server< tuw_ellipses::EllipsesDetectionConfig >::CallbackType reconfigureFnc_
#define TUW_ELLIPSES_NODE_PUBLISH_TF
#define TUW_ELLIPSES_NODE_DEFAULT_SHOW_CAMERA_IMAGE
#define TUW_ELLIPSES_NODE_DEFAULT_SHOW_CAMERA_IMAGE_WAITKEY
ROSCPP_DECL const std::string & getNamespace()
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
#define TUW_ELLIPSES_NODE_PUBLISH_FIDUCIALS
#define TUW_ELLIPSES_NODE_DEFAULT_SKIP_SECOND_TF
#define TUW_ELLIPSES_NODE_DEFAULT_DEBUG_FREEZE
bool getParam(const std::string &key, std::string &s) const
#define TUW_ELLIPSES_NODE_PUBLISH_MARKER
void callbackParameters(tuw_ellipses::EllipsesDetectionConfig &config, uint32_t level)


tuw_ellipses
Author(s): Markus Bader
autogenerated on Mon Jun 10 2019 15:42:10