__init__.py
Go to the documentation of this file.
1 # Generic set of parameters required by any MBF-based navigation framework
2 # To use:
3 #
4 # from mbf_abstract_nav import add_mbf_abstract_nav_params
5 # gen = ParameterGenerator()
6 # add_mbf_abstract_nav_params(gen)
7 # ...
8 # WARN: parameters added here must be copied on the specific MBF implementation reconfigure callback, e.g. in:
9 # https://github.com/magazino/move_base_flex/blob/master/mbf_costmap_nav/src/mbf_costmap_nav/costmap_navigation_server.cpp#L130
10 # Also, you need to touch https://github.com/magazino/move_base_flex/blob/master/mbf_costmap_nav/cfg/MoveBaseFlex.cfg
11 # when recompiling to ensure configuration code is regenerated with the new parameters
12 
13 # need this only for dataype declarations
14 from dynamic_reconfigure.parameter_generator_catkin import str_t, double_t, int_t, bool_t
15 
16 
18  gen.add("planner_frequency", double_t, 0,
19  "The rate in Hz at which to run the planning loop.", 0, 0, 100)
20  gen.add("planner_patience", double_t, 0,
21  "How long the planner will wait in seconds in an attempt to find a valid plan before giving up.", 5.0, 0, 100)
22  gen.add("planner_max_retries", int_t, 0,
23  "How many times we will recall the planner in an attempt to find a valid plan before giving up", -1, -1, 1000)
24 
25  gen.add("controller_frequency", double_t, 0,
26  "The rate in Hz at which to run the control loop and send velocity commands to the base.", 20, 0, 100)
27  gen.add("controller_patience", double_t, 0,
28  "How long the controller will wait in seconds without receiving a valid control before giving up.", 5.0, 0, 100)
29  gen.add("controller_max_retries", int_t, 0,
30  "How many times we will recall the controller in an attempt to find a valid comand before giving up", -1, -1, 1000)
31 
32  gen.add("recovery_enabled", bool_t, 0,
33  "Whether or not to enable the move_base_flex recovery behaviors to attempt to clear out space.", True)
34  gen.add("recovery_patience", double_t, 0,
35  "How much time we allow recovery behaviors to complete before canceling (or stopping if cancel fails) them", 15.0, 0, 100)
36 
37  gen.add("oscillation_timeout", double_t, 0,
38  "How long in seconds to allow for oscillation before executing recovery behaviors.", 0.0, 0, 60)
39  gen.add("oscillation_distance", double_t, 0,
40  "How far in meters the robot must move to be considered not to be oscillating.", 0.5, 0, 10)
def add_mbf_abstract_nav_params(gen)
Definition: __init__.py:17


mbf_abstract_nav
Author(s): Sebastian Pütz
autogenerated on Tue Jun 18 2019 19:34:34