__init__.py
Go to the documentation of this file.
00001 # Generic set of parameters required by any MBF-based navigation framework
00002 # To use:
00003 #
00004 #  from mbf_abstract_nav import add_mbf_abstract_nav_params
00005 #  gen = ParameterGenerator()
00006 #  add_mbf_abstract_nav_params(gen)
00007 #  ...
00008 # WARN: parameters added here must be copied on the specific MBF implementation reconfigure callback, e.g. in:
00009 #       https://github.com/magazino/move_base_flex/blob/master/mbf_costmap_nav/src/mbf_costmap_nav/costmap_navigation_server.cpp#L130
00010 # Also, you need to touch https://github.com/magazino/move_base_flex/blob/master/mbf_costmap_nav/cfg/MoveBaseFlex.cfg
00011 # when recompiling to ensure configuration code is regenerated with the new parameters
00012 
00013 # need this only for dataype declarations
00014 from dynamic_reconfigure.parameter_generator_catkin import str_t, double_t, int_t, bool_t
00015 
00016 
00017 def add_mbf_abstract_nav_params(gen):
00018     gen.add("planner_frequency", double_t, 0,
00019             "The rate in Hz at which to run the planning loop.", 0, 0, 100)
00020     gen.add("planner_patience", double_t, 0,
00021             "How long the planner will wait in seconds in an attempt to find a valid plan before giving up.", 5.0, 0, 100)
00022     gen.add("planner_max_retries", int_t, 0,
00023             "How many times we will recall the planner in an attempt to find a valid plan before giving up", -1, -1, 1000)
00024 
00025     gen.add("controller_frequency", double_t, 0,
00026             "The rate in Hz at which to run the control loop and send velocity commands to the base.", 20, 0, 100)
00027     gen.add("controller_patience", double_t, 0,
00028             "How long the controller will wait in seconds without receiving a valid control before giving up.", 5.0, 0, 100)
00029     gen.add("controller_max_retries", int_t, 0,
00030             "How many times we will recall the controller in an attempt to find a valid comand before giving up", -1, -1, 1000)
00031 
00032     gen.add("recovery_enabled", bool_t, 0,
00033             "Whether or not to enable the move_base_flex recovery behaviors to attempt to clear out space.", True)
00034     gen.add("recovery_patience", double_t, 0,
00035             "How much time we allow recovery behaviors to complete before canceling (or stopping if cancel fails) them", 15.0, 0, 100)
00036 
00037     gen.add("oscillation_timeout", double_t, 0,
00038             "How long in seconds to allow for oscillation before executing recovery behaviors.", 0.0, 0, 60)
00039     gen.add("oscillation_distance", double_t, 0,
00040             "How far in meters the robot must move to be considered not to be oscillating.", 0.5, 0, 10)


mbf_abstract_nav
Author(s): Sebastian Pütz
autogenerated on Mon Jun 17 2019 20:11:35