Make ament_flake8 pass (#299)
Set of hand-made changes to let ament_flake8 pass
This commit is contained in:
parent
63cee139f1
commit
9689971aee
@ -1,20 +1,47 @@
|
|||||||
#! /usr/bin/env python
|
#! /usr/bin/env python
|
||||||
|
|
||||||
|
from dynamic_reconfigure.parameter_generator_catkin import int_t
|
||||||
|
from dynamic_reconfigure.parameter_generator_catkin import double_t
|
||||||
|
from dynamic_reconfigure.parameter_generator_catkin import bool_t
|
||||||
|
from dynamic_reconfigure.parameter_generator_catkin import str_t
|
||||||
|
|
||||||
# set up parameters that we care about
|
# set up parameters that we care about
|
||||||
PACKAGE = 'pcl_ros'
|
PACKAGE = 'pcl_ros'
|
||||||
|
|
||||||
from dynamic_reconfigure.parameter_generator_catkin import *;
|
|
||||||
|
|
||||||
def add_common_parameters(gen):
|
def add_common_parameters(gen):
|
||||||
# add (self, name, paramtype, level, description, default = None, min = None, max = None, edit_method = "")
|
# add(self, name, paramtype, level, description, default = None, min = None,
|
||||||
gen.add ("max_iterations", int_t, 0, "The maximum number of iterations the algorithm will run for", 50, 0, 100000)
|
# max = None, edit_method = "")
|
||||||
gen.add ("probability", double_t, 0, "The desired probability of choosing at least one sample free from outliers", 0.99, 0.5, 0.99)
|
gen.add("max_iterations", int_t, 0,
|
||||||
gen.add ("distance_threshold", double_t, 0, "The distance to model threshold", 0.02, 0, 1.0)
|
"The maximum number of iterations the algorithm will run for",
|
||||||
gen.add ("optimize_coefficients", bool_t, 0, "Model coefficient refinement", True)
|
50, 0, 100000)
|
||||||
gen.add ("radius_min", double_t, 0, "The minimum allowed model radius (where applicable)", 0.0, 0, 1.0)
|
gen.add("probability", double_t, 0,
|
||||||
gen.add ("radius_max", double_t, 0, "The maximum allowed model radius (where applicable)", 0.05, 0, 1.0)
|
"The desired probability of choosing at least one sample free from outliers",
|
||||||
gen.add ("eps_angle", double_t, 0, "The maximum allowed difference between the model normal and the given axis in radians.", 0.17, 0.0, 1.5707)
|
0.99, 0.5, 0.99)
|
||||||
gen.add ("min_inliers", int_t, 0, "The minimum number of inliers a model must have in order to be considered valid.", 0, 0, 100000)
|
gen.add("distance_threshold", double_t, 0,
|
||||||
gen.add ("input_frame", str_t, 0, "The input TF frame the data should be transformed into, if input.header.frame_id is different.", "")
|
"The distance to model threshold",
|
||||||
gen.add ("output_frame", str_t, 0, "The output TF frame the data should be transformed into, if input.header.frame_id is different.", "")
|
0.02, 0, 1.0)
|
||||||
|
gen.add("optimize_coefficients", bool_t, 0,
|
||||||
|
"Model coefficient refinement",
|
||||||
|
True)
|
||||||
|
gen.add("radius_min", double_t, 0,
|
||||||
|
"The minimum allowed model radius (where applicable)",
|
||||||
|
0.0, 0, 1.0)
|
||||||
|
gen.add("radius_max", double_t, 0,
|
||||||
|
"The maximum allowed model radius (where applicable)",
|
||||||
|
0.05, 0, 1.0)
|
||||||
|
gen.add("eps_angle", double_t, 0,
|
||||||
|
("The maximum allowed difference between the model normal "
|
||||||
|
"and the given axis in radians."),
|
||||||
|
0.17, 0.0, 1.5707)
|
||||||
|
gen.add("min_inliers", int_t, 0,
|
||||||
|
"The minimum number of inliers a model must have in order to be considered valid.",
|
||||||
|
0, 0, 100000)
|
||||||
|
gen.add("input_frame", str_t, 0,
|
||||||
|
("The input TF frame the data should be transformed into, "
|
||||||
|
"if input.header.frame_id is different."),
|
||||||
|
"")
|
||||||
|
gen.add("output_frame", str_t, 0,
|
||||||
|
("The output TF frame the data should be transformed into, "
|
||||||
|
"if input.header.frame_id is different."),
|
||||||
|
"")
|
||||||
|
|||||||
@ -1,17 +1,36 @@
|
|||||||
#! /usr/bin/env python
|
#! /usr/bin/env python
|
||||||
|
|
||||||
|
from dynamic_reconfigure.parameter_generator_catkin import str_t
|
||||||
|
from dynamic_reconfigure.parameter_generator_catkin import double_t
|
||||||
|
from dynamic_reconfigure.parameter_generator_catkin import bool_t
|
||||||
|
|
||||||
# set up parameters that we care about
|
# set up parameters that we care about
|
||||||
PACKAGE = 'pcl_ros'
|
PACKAGE = 'pcl_ros'
|
||||||
|
|
||||||
from dynamic_reconfigure.parameter_generator_catkin import *;
|
|
||||||
|
|
||||||
def add_common_parameters(gen):
|
def add_common_parameters(gen):
|
||||||
# def add (self, name, paramtype, level, description, default = None, min = None, max = None, edit_method = ""):
|
# def add (self, name, paramtype, level, description, default = None, min = None,
|
||||||
|
# max = None, edit_method = ""):
|
||||||
gen.add("filter_field_name", str_t, 0, "The field name used for filtering", "z")
|
gen.add("filter_field_name", str_t, 0, "The field name used for filtering", "z")
|
||||||
gen.add ("filter_limit_min", double_t, 0, "The minimum allowed field value a point will be considered from", 0.0, -100000.0, 100000.0)
|
gen.add("filter_limit_min", double_t, 0,
|
||||||
gen.add ("filter_limit_max", double_t, 0, "The maximum allowed field value a point will be considered from", 1.0, -100000.0, 100000.0)
|
"The minimum allowed field value a point will be considered from",
|
||||||
gen.add ("filter_limit_negative", bool_t, 0, "Set to true if we want to return the data outside [filter_limit_min; filter_limit_max].", False)
|
0.0, -100000.0, 100000.0)
|
||||||
gen.add ("keep_organized", bool_t, 0, "Set whether the filtered points should be kept and set to NaN, or removed from the PointCloud, thus potentially breaking its organized structure.", False)
|
gen.add("filter_limit_max", double_t, 0,
|
||||||
gen.add ("input_frame", str_t, 0, "The input TF frame the data should be transformed into before processing, if input.header.frame_id is different.", "")
|
"The maximum allowed field value a point will be considered from",
|
||||||
gen.add ("output_frame", str_t, 0, "The output TF frame the data should be transformed into after processing, if input.header.frame_id is different.", "")
|
1.0, -100000.0, 100000.0)
|
||||||
|
gen.add("filter_limit_negative", bool_t, 0,
|
||||||
|
("Set to true if we want to return the data outside "
|
||||||
|
"[filter_limit_min; filter_limit_max]."),
|
||||||
|
False)
|
||||||
|
gen.add("keep_organized", bool_t, 0,
|
||||||
|
("Set whether the filtered points should be kept and set to NaN, "
|
||||||
|
"or removed from the PointCloud, thus potentially breaking its organized structure."),
|
||||||
|
False)
|
||||||
|
gen.add("input_frame", str_t, 0,
|
||||||
|
("The input TF frame the data should be transformed into before processing, "
|
||||||
|
"if input.header.frame_id is different."),
|
||||||
|
"")
|
||||||
|
gen.add("output_frame", str_t, 0,
|
||||||
|
("The output TF frame the data should be transformed into after processing, "
|
||||||
|
"if input.header.frame_id is different."),
|
||||||
|
"")
|
||||||
|
|||||||
Loading…
x
Reference in New Issue
Block a user