cuboid_parameter.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # set up parameters that we care about
00004 PACKAGE = 'jsk_pcl_ros'
00005 
00006 try:
00007     import imp
00008     imp.find_module(PACKAGE)
00009     from dynamic_reconfigure.parameter_generator_catkin import *;
00010 except:
00011     import roslib; roslib.load_manifest(PACKAGE)
00012     from dynamic_reconfigure.parameter_generator import *;
00013 gen = ParameterGenerator ()
00014 
00015 gen.add("use_range_likelihood", bool_t, 0, "", False)
00016 gen.add("range_likelihood_local_min_z", double_t, 0, "", 0.0, 0.0, 1.0)
00017 gen.add("range_likelihood_local_max_z", double_t, 0, "", 0.0, 0.0, 1.0)
00018 gen.add("use_occlusion_likelihood", bool_t, 0, "", False)
00019 gen.add("min_inliers", int_t, 0, "", 10, 0, 1000)
00020 gen.add("outlier_distance", double_t, 0, "", 0.1, 0.0, 1.0)
00021 gen.add("plane_distance_error_power", double_t, 0, "", 2, 0, 10)
00022 gen.add("use_support_plane_angular_likelihood", bool_t, 0, "", False)
00023 gen.add("support_plane_angular_likelihood_weight_power", double_t, 0, "", 1.0, 0.0, 10.0)
00024 gen.add("use_surface_area_likelihood", bool_t, 0, "", False)
00025 gen.add("surface_area_error_power", double_t, 0, "", 1.0, 0.0, 10.0)
00026 gen.add("use_polygon_likelihood", bool_t, 0, "", False)
00027 # CMake do not know dependency between this script and
00028 # PlaneSupportedCuboidEstimator.cfg and InteractiveCuboidLikelihood.cfg.
00029 # So you need to run following command when you edit cuboid_parameter.py
00030 # touch $(rospack find jsk_pcl_ros)/cfg/{PlaneSupportedCuboidEstimator.cfg,InteractiveCuboidLikelihood.cfg}


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Wed Sep 16 2015 04:36:47