00001 /****************************************************************************** 00002 * \file 00003 * 00004 * $Id: plane_detector_params.h 693 2012-04-20 09:22:39Z ihulik $ 00005 * 00006 * Copyright (C) Brno University of Technology 00007 * 00008 * This file is part of software developed by dcgm-robotics@FIT group. 00009 * 00010 * Author: Rostislav Hulik (ihulik@fit.vutbr.cz) 00011 * Supervised by: Michal Spanel (spanel@fit.vutbr.cz) 00012 * Date: 15.06.2012 (version 1.0) 00013 * 00014 * This file is free software: you can redistribute it and/or modify 00015 * it under the terms of the GNU Lesser General Public License as published by 00016 * the Free Software Foundation, either version 3 of the License, or 00017 * (at your option) any later version. 00018 * 00019 * This file is distributed in the hope that it will be useful, 00020 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00021 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00022 * GNU Lesser General Public License for more details. 00023 * 00024 * You should have received a copy of the GNU Lesser General Public License 00025 * along with this file. If not, see <http://www.gnu.org/licenses/>. 00026 */ 00027 00028 #pragma once 00029 #ifndef PLANE_DETECTOR_PARAMS_H 00030 #define PLANE_DETECTOR_PARAMS_H 00031 00032 #include <string> 00033 #include "srs_env_model_percp/topics_list.h" 00034 #include "srs_env_model_percp/but_segmentation/normals.h" 00035 namespace srs_env_model_percp 00036 { 00040 const std::string PARAM_NODE_INPUT = "planedet_input"; 00041 const std::string PARAM_NODE_INPUT_PCL = "pcl"; 00042 const std::string PARAM_NODE_INPUT_KINECT = "kinect"; 00043 const std::string PARAM_NODE_INPUT_DEFAULT = PARAM_NODE_INPUT_PCL; 00044 00049 const std::string PARAM_NODE_ORIGINAL_FRAME = "original_frame"; 00050 const std::string PARAM_NODE_ORIGINAL_FRAME_DEFAULT = "/head_cam3d_link"; 00051 00055 const std::string PARAM_NODE_OUTPUT_FRAME = "global_frame"; 00056 const std::string PARAM_NODE_OUTPUT_FRAME_DEFAULT = "/map"; 00057 00058 00062 const std::string PARAM_HT_MAXDEPTH = "planedet_ht_maxdepth"; 00063 const double PARAM_HT_MAXDEPTH_DEFAULT = 100.0; 00064 00065 const std::string PARAM_HT_MAXHEIGHT = "planedet_ht_max_height"; 00066 const double PARAM_HT_MAXHEIGHT_DEFAULT = 3.0; 00067 00068 const std::string PARAM_HT_MINHEIGHT = "planedet_ht_min_height"; 00069 const double PARAM_HT_MINHEIGHT_DEFAULT = 0.1; 00070 00071 const std::string PARAM_HT_MINSHIFT = "planedet_ht_minshift"; 00072 const double PARAM_HT_MINSHIFT_DEFAULT = -40.0; 00073 00074 const std::string PARAM_HT_MAXSHIFT = "planedet_ht_maxshift"; 00075 const double PARAM_HT_MAXSHIFT_DEFAULT = 40.0; 00076 00077 const std::string PARAM_HT_ANGLE_RES = "planedet_ht_angle_res"; 00078 const double PARAM_HT_ANGLE_RES_DEFAULT = 512; 00079 00080 const std::string PARAM_HT_SHIFT_RES = "planedet_ht_shift_res"; 00081 const double PARAM_HT_SHIFT_RES_DEFAULT = 4096; 00082 00083 const std::string PARAM_HT_GAUSS_ANGLE_RES = "planedet_ht_gauss_angle_res"; 00084 const double PARAM_HT_GAUSS_ANGLE_RES_DEFAULT = 11; 00085 00086 const std::string PARAM_HT_GAUSS_SHIFT_RES = "planedet_ht_gauss_shift_res"; 00087 const double PARAM_HT_GAUSS_SHIFT_RES_DEFAULT = 11; 00088 00089 const std::string PARAM_HT_GAUSS_ANGLE_SIGMA = "planedet_ht_gauss_angle_sigma"; 00090 const double PARAM_HT_GAUSS_ANGLE_SIGMA_DEFAULT = 0.04; 00091 00092 const std::string PARAM_HT_GAUSS_SHIFT_SIGMA = "planedet_ht_gauss_shift_sigma"; 00093 const double PARAM_HT_GAUSS_SHIFT_SIGMA_DEFAULT = 0.15; 00094 00095 const std::string PARAM_HT_LVL1_GAUSS_ANGLE_RES = "planedet_ht_lvl1_gauss_angle_res"; 00096 const double PARAM_HT_LVL1_GAUSS_ANGLE_RES_DEFAULT = 21; 00097 00098 const std::string PARAM_HT_LVL1_GAUSS_SHIFT_RES = "planedet_ht_lvl1_gauss_shift_res"; 00099 const double PARAM_HT_LVL1_GAUSS_SHIFT_RES_DEFAULT = 21; 00100 00101 const std::string PARAM_HT_LVL1_GAUSS_ANGLE_SIGMA = "planedet_ht_lvl1_gauss_angle_sigma"; 00102 const double PARAM_HT_LVL1_GAUSS_ANGLE_SIGMA_DEFAULT = 5.0; 00103 00104 const std::string PARAM_HT_LVL1_GAUSS_SHIFT_SIGMA = "planedet_ht_lvl1_gauss_shift_sigma"; 00105 const double PARAM_HT_LVL1_GAUSS_SHIFT_SIGMA_DEFAULT = 5.0; 00106 00107 const std::string PARAM_HT_KEEPTRACK = "planedet_ht_keep_track"; 00108 const int PARAM_HT_KEEPTRACK_DEFAULT = 1; 00109 00110 const std::string PARAM_HT_PLANE_MERGE_SHIFT = "planedet_ht_plane_merge_shift"; 00111 const double PARAM_HT_PLANE_MERGE_SHIFT_DEFAULT = 0.1; 00112 00113 const std::string PARAM_HT_PLANE_MERGE_ANGLE = "planedet_ht_plane_merge_angle"; 00114 const double PARAM_HT_PLANE_MERGE_ANGLE_DEFAULT = 0.3; 00115 00116 const std::string PARAM_HT_MIN_SMOOTH = "planedet_ht_min_smooth"; 00117 const int PARAM_HT_MIN_SMOOTH_DEFAULT = 50; 00118 00119 const std::string PARAM_HT_STEP_SUBSTRACTION = "planedet_ht_step_substraction"; 00120 const double PARAM_HT_STEP_SUBSTRACTION_DEFAULT = 0.2; 00121 00122 00126 const std::string PARAM_SEARCH_MINIMUM_CURRENT_SPACE = "planedet_search_minimum_current_space"; 00127 const double PARAM_SEARCH_MINIMUM_CURRENT_SPACE_DEFAULT = 1500.0; 00128 00129 const std::string PARAM_SEARCH_MINIMUM_GLOBAL_SPACE = "planedet_search_minimum_global_space"; 00130 const double PARAM_SEARCH_MINIMUM_GLOBAL_SPACE_DEFAULT = 1.5; 00131 00132 const std::string PARAM_SEARCH_MAXIMA_SEARCH_NEIGHBORHOOD = "planedet_search_maxima_search_neighborhood"; 00133 const int PARAM_SEARCH_MAXIMA_SEARCH_NEIGHBORHOOD_DEFAULT = 1; 00134 00135 const std::string PARAM_SEARCH_MAXIMA_SEARCH_BLUR = "planedet_search_maxima_search_blur"; 00136 const int PARAM_SEARCH_MAXIMA_SEARCH_BLUR_DEFAULT = 0; 00137 00138 00142 const std::string PARAM_VISUALISATION_DISTANCE = "planedet_visualisation_distance"; 00143 const double PARAM_VISUALISATION_DISTANCE_DEFAULT = 0.05; 00144 00145 const std::string PARAM_VISUALISATION_MIN_COUNT = "planedet_visualisation_min_count"; 00146 const int PARAM_VISUALISATION_MIN_COUNT_DEFAULT = 2000; 00147 00148 const std::string PARAM_VISUALISATION_PLANE_NORMAL_DEV = "planedet_visualisation_plane_normal_dev"; 00149 const double PARAM_VISUALISATION_PLANE_NORMAL_DEV_DEFAULT = 0.15; 00150 00151 const std::string PARAM_VISUALISATION_PLANE_SHIFT_DEV = "planedet_visualisation_plane_shift_dev"; 00152 const double PARAM_VISUALISATION_PLANE_SHIFT_DEV_DEFAULT = 0.45; 00153 00154 const std::string PARAM_VISUALISATION_COLOR = "planedet_visualisation_color"; 00155 const std::string PARAM_VISUALISATION_COLOR_DEFAULT = "plane_eq"; 00156 00157 const std::string PARAM_VISUALISATION_TTL = "planedet_visualisation_ttl"; 00158 const int PARAM_VISUALISATION_TTL_DEFAULT = 10; // sec 00159 00160 const std::string PARAM_VISUALISATION_MAX_POLY_SIZE = "planedet_max_poly_size"; 00161 const int PARAM_VISUALISATION_MAX_POLY_SIZE_DEFAULT = 2000; // sec 00162 00163 00167 const std::string PARAM_NORMAL_TYPE = "planedet_normal_type"; 00168 const int PARAM_NORMAL_TYPE_DEFAULT = but_plane_detector::NormalType::PCL; 00169 00170 const std::string PARAM_NORMAL_NEIGHBORHOOD = "planedet_normal_neighborhood"; 00171 const int PARAM_NORMAL_NEIGHBORHOOD_DEFAULT = 5; // sec 00172 00173 const std::string PARAM_NORMAL_THRESHOLD = "planedet_normal_threshold"; 00174 const double PARAM_NORMAL_THRESHOLD_DEFAULT = 0.2; // sec 00175 00176 const std::string PARAM_NORMAL_OUTLIERTHRESH = "planedet_normal_outlierThreshold"; 00177 const double PARAM_NORMAL_OUTLIERTHRESH_DEFAULT = 0.02; // sec 00178 00179 const std::string PARAM_NORMAL_ITER = "planedet_normal_iter"; 00180 const int PARAM_NORMAL_ITER_DEFAULT = 3; // sec 00181 00185 struct PlaneDetectorSettings 00186 { 00187 std::string param_node_input; 00188 std::string param_output_frame; 00189 std::string param_original_frame; 00190 00191 double param_ht_maxdepth; 00192 double param_ht_maxheight; 00193 double param_ht_minheight; 00194 int param_ht_keeptrack; 00195 double param_ht_minshift; 00196 double param_ht_maxshift; 00197 double param_ht_angle_res; 00198 double param_ht_shift_res; 00199 double param_ht_gauss_angle_res; 00200 double param_ht_gauss_shift_res; 00201 double param_ht_gauss_angle_sigma; 00202 double param_ht_gauss_shift_sigma; 00203 double param_ht_lvl1_gauss_angle_res; 00204 double param_ht_lvl1_gauss_shift_res; 00205 double param_ht_lvl1_gauss_angle_sigma; 00206 double param_ht_lvl1_gauss_shift_sigma; 00207 double param_ht_step_substraction; 00208 00209 double param_ht_plane_merge_shift; 00210 double param_ht_plane_merge_angle; 00211 int param_ht_min_smooth; 00212 00213 double param_search_minimum_current_space; 00214 double param_search_minimum_global_space; 00215 int param_search_maxima_search_neighborhood; 00216 int param_search_maxima_search_blur; 00217 00218 double param_visualisation_distance; 00219 double param_visualisation_plane_normal_dev; 00220 double param_visualisation_plane_shift_dev; 00221 int param_visualisation_min_count; 00222 int param_visualisation_ttl; 00223 int param_visualisation_max_poly_size; 00224 00225 int param_normal_type; 00226 int param_normal_neighborhood; 00227 double param_normal_threshold; 00228 double param_normal_outlierThreshold; 00229 int param_normal_iter; 00230 00231 std::string param_visualisation_color; 00232 }; 00233 } 00234 00235 00236 #endif