ellipses_nodelet_parameters.cpp
Go to the documentation of this file.
00001 /***************************************************************************
00002  * Copyright (c) 2014 Markus Bader <markus.bader@tuwien.ac.at>
00003  * All rights reserved.
00004  * 
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  * 1. Redistributions of source code must retain the above copyright
00008  *    notice, this list of conditions and the following disclaimer.
00009  * 2. Redistributions in binary form must reproduce the above copyright
00010  *    notice, this list of conditions and the following disclaimer in the
00011  *    documentation and/or other materials provided with the distribution.
00012  * 3. All advertising materials mentioning features or use of this software
00013  *    must display the following acknowledgement:
00014  *    This product includes software developed by the TU-Wien.
00015  * 4. Neither the name of the TU-Wien nor the
00016  *    names of its contributors may be used to endorse or promote products
00017  *    derived from this software without specific prior written permission.
00018  * 
00019  * THIS SOFTWARE IS PROVIDED BY Markus Bader ''AS IS'' AND ANY
00020  * EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00021  * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00022  * DISCLAIMED. IN NO EVENT SHALL Markus Bader BE LIABLE FOR ANY
00023  * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00024  * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00025  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00026  * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00027  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00028  * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00029  ***************************************************************************/
00030 
00031 #include "ellipses_nodelet.h"
00032 #include "ellipses_nodelet_defaults.h"
00033 
00034 using namespace tuw;
00035 
00036 EllipsesDetectionNode::ParametersNode::ParametersNode()
00037     : Parameters() 
00038     , node("~")
00039     , node_name(node.getNamespace())
00040     , debug_freeze(TUW_ELLIPSES_NODE_DEFAULT_DEBUG_FREEZE)
00041     , show_camera_image(TUW_ELLIPSES_NODE_DEFAULT_SHOW_CAMERA_IMAGE)
00042     , show_camera_image_waitkey(TUW_ELLIPSES_NODE_DEFAULT_SHOW_CAMERA_IMAGE_WAITKEY)
00043     , image_skip(TUW_ELLIPSES_NODE_DEFAULT_IMAGE_SKIP)
00044     , skip_second_tf(TUW_ELLIPSES_NODE_DEFAULT_SKIP_SECOND_TF)
00045     , tf_prefix(node_name)
00046     {
00047     node.getParam("debug_freeze", debug_freeze);
00048     ROS_INFO("%s - debug_freeze:  %s", node_name.c_str(), (debug_freeze ? "true" : "false"));
00049     node.getParam("show_camera_image", show_camera_image);
00050     ROS_INFO("%s - show_camera_image:  %s", node_name.c_str(), (show_camera_image ? "true" : "false"));
00051     node.getParam("show_camera_image_waitkey", show_camera_image_waitkey);
00052     ROS_INFO("%s - show_camera_image_waitkey: %i", node_name.c_str(), show_camera_image_waitkey);
00053     node.getParam("image_skip", image_skip);
00054     ROS_INFO("%s - image_skip: %i", node_name.c_str(), image_skip);
00055     node.param<std::string>("tf_prefix", tf_prefix, node_name);
00056     ROS_INFO("%s: tf_prefix: %s", node_name.c_str(), tf_prefix.c_str());
00057     node.getParam("skip_second_tf", skip_second_tf);
00058     ROS_INFO("%s - skip_second_tf:  %s", node_name.c_str(), (skip_second_tf ? "true" : "false"));
00059 
00060     reconfigureFnc_ = boost::bind(&EllipsesDetectionNode::ParametersNode::callbackParameters, this ,  _1, _2);
00061     reconfigureServer_.setCallback(reconfigureFnc_);
00062 
00063 
00064 }
00065 
00066 
00067 void EllipsesDetectionNode::ParametersNode::callbackParameters (tuw_ellipses::EllipsesDetectionConfig &config, uint32_t level ) {
00068   int kernal_sizes[] = {1, 3, 5, 7};
00069   show_camera_image = config.show_camera_image;
00070   show_camera_image_waitkey = config.show_camera_image_waitkey;
00071   debug = config.debug;
00072   distorted_input = config.distorted_input;
00073   debug_freeze = config.debug_freeze;
00074   image_skip = config.image_skip;
00075   edge_detection = (EdgeDetection) config.edge_detection;
00076   threshold_edge_detection1 = config.threshold_edge_detection1;
00077   threshold_edge_detection2 = config.threshold_edge_detection2;
00078   if(config.kernel_size_edge_detection > 7) kernel_size_edge_detection = 7;
00079   else if(config.kernel_size_edge_detection < 3) kernel_size_edge_detection = 3;
00080   else if(config.kernel_size_edge_detection % 2) kernel_size_edge_detection = config.kernel_size_edge_detection;
00081   else kernel_size_edge_detection = config.kernel_size_edge_detection+1;
00082   edge_linking = (EdgeLinking) config.edge_linking;
00083   threshold_contour_min_points = config.threshold_contour_min_points;
00084   threshold_polygon = config.threshold_polygon;
00085   filter_convex = config.filter_convex;
00086   ellipse_redefinement = config.ellipse_redefinement;
00087   threshold_rotated_rect_ratio = config.threshold_rotated_rect_ratio;
00088   filter_contour_mean = config.filter_contour_mean;
00089   threshold_min_radius = config.threshold_min_radius;
00090   threshold_max_radius = config.threshold_max_radius;
00091   filter_rings = config.filter_rings;
00092   threshold_ring_center = config.threshold_ring_center;
00093   threshold_ring_ratio = config.threshold_ring_ratio;
00094   pose_estimation = (PoseEstimation) config.pose_estimation;
00095   circle_diameter = config.circle_diameter;
00096   skip_second_tf = config.skip_second_tf;
00097   
00098 }


tuw_ellipses
Author(s):
autogenerated on Sun May 29 2016 02:50:24