Show EOL distros: 

move_base_flex: mbf_abstract_core | mbf_abstract_nav | mbf_costmap_core | mbf_costmap_nav | mbf_msgs | mbf_simple_nav

Package Summary

Move Base Flex (MBF) is a backwards-compatible replacement for move_base. MBF can use existing plugins for move_base, and provides an enhanced version of the planner, controller and recovery plugin ROS interfaces. It exposes action servers for planning, controlling and recovering, providing detailed information of the current state and the plugin’s feedback. An external executive logic can use MBF and its actions to perform smart and flexible navigation strategies. Furthermore, MBF enables the use of other map representations, e.g. meshes or grid_map This package is a meta package and refers to the Move Base Flex stack packages.The abstract core of MBF – without any binding to a map representation – is represented by the mbf_abstract_nav and the mbf_abstract_core. For navigation on costmaps see mbf_costmap_nav and mbf_costmap_core.

move_base_flex: mbf_abstract_core | mbf_abstract_nav | mbf_costmap_core | mbf_costmap_nav | mbf_msgs | mbf_simple_nav | mbf_utility

Package Summary

Move Base Flex (MBF) is a backwards-compatible replacement for move_base. MBF can use existing plugins for move_base, and provides an enhanced version of the planner, controller and recovery plugin ROS interfaces. It exposes action servers for planning, controlling and recovering, providing detailed information of the current state and the plugin’s feedback. An external executive logic can use MBF and its actions to perform smart and flexible navigation strategies. Furthermore, MBF enables the use of other map representations, e.g. meshes or grid_map This package is a meta package and refers to the Move Base Flex stack packages.The abstract core of MBF – without any binding to a map representation – is represented by the mbf_abstract_nav and the mbf_abstract_core. For navigation on costmaps see mbf_costmap_nav and mbf_costmap_core.

move_base_flex: mbf_abstract_core | mbf_abstract_nav | mbf_costmap_core | mbf_costmap_nav | mbf_msgs | mbf_simple_nav

Package Summary

Move Base Flex (MBF) is a backwards-compatible replacement for move_base. MBF can use existing plugins for move_base, and provides an enhanced version of the planner, controller and recovery plugin ROS interfaces. It exposes action servers for planning, controlling and recovering, providing detailed information of the current state and the plugin’s feedback. An external executive logic can use MBF and its actions to perform smart and flexible navigation strategies. Furthermore, MBF enables the use of other map representations, e.g. meshes or grid_map This package is a meta package and refers to the Move Base Flex stack packages.The abstract core of MBF – without any binding to a map representation – is represented by the mbf_abstract_nav and the mbf_abstract_core. For navigation on costmaps see mbf_costmap_nav and mbf_costmap_core.

move_base_flex: mbf_abstract_core | mbf_abstract_nav | mbf_costmap_core | mbf_costmap_nav | mbf_msgs | mbf_simple_nav | mbf_utility

Package Summary

Move Base Flex (MBF) is a backwards-compatible replacement for move_base. MBF can use existing plugins for move_base, and provides an enhanced version of the planner, controller and recovery plugin ROS interfaces. It exposes action servers for planning, controlling and recovering, providing detailed information of the current state and the plugin’s feedback. An external executive logic can use MBF and its actions to perform smart and flexible navigation strategies. Furthermore, MBF enables the use of other map representations, e.g. meshes or grid_map This package is a meta package and refers to the Move Base Flex stack packages.The abstract core of MBF – without any binding to a map representation – is represented by the mbf_abstract_nav and the mbf_abstract_core. For navigation on costmaps see mbf_costmap_nav and mbf_costmap_core.

move_base_flex: mbf_abstract_core | mbf_abstract_nav | mbf_costmap_core | mbf_costmap_nav | mbf_msgs | mbf_simple_nav | mbf_utility

Package Summary

Move Base Flex (MBF) is a backwards-compatible replacement for move_base. MBF can use existing plugins for move_base, and provides an enhanced version of the planner, controller and recovery plugin ROS interfaces. It exposes action servers for planning, controlling and recovering, providing detailed information of the current state and the plugin’s feedback. An external executive logic can use MBF and its actions to perform smart and flexible navigation strategies. Furthermore, MBF enables the use of other map representations, e.g. meshes or grid_map This package is a meta package and refers to the Move Base Flex stack packages.The abstract core of MBF – without any binding to a map representation – is represented by the mbf_abstract_nav and the mbf_abstract_core. For navigation on costmaps see mbf_costmap_nav and mbf_costmap_core.

Move Base Flex - A highly flexible navigation framework -

Overview

Move Base Flex (MBF) is a backwards-compatible replacement for move_base. MBF can use existing plugins for move_base, and provides an enhanced version of the same ROS interface. It exposes action servers for planning, controlling and recovering, providing detailed information of the current state and the plugin's feedback. An external executive logic can use MBF and its actions to perform smart and flexible navigation strategies. For example, Magazino has successfully deployed MBF at customer facilities to control TORU robots in highly dynamical environments. Furthermore, MBF enables the use of other map representations, e.g. meshes. The core features are:

  • Fully backwards-compatible with current ROS navigation.
  • Actions for the submodules planning, controlling and recovering, and services to query the costmaps are provided. This interface allows external executives, e.g. SMACH, or Behavior Trees, to run highly flexible and complex navigation strategies.
  • Can load multiple planners and controllers; the executive can select the appropriate one, or even run several in parallel.
  • Comprehensive result and feedback information on all actions, including error codes and messages from the loaded plugins. For users still relying on a unique navigation interface, we have extended move_base action with detailed result and feedback information (though we still provide the current one).
  • Separation between an abstract navigation framework and concrete implementations, allowing faster development of new applications, e.g. 3D navigation.

You can find more information in the paper: "Move Base Flex: A Highly Flexible Navigation Framework for Mobile Robots" by Sebastian Pütz, Jorge Santos, and Joachim Hertzberg

BibTeX:

@inproceedings{puetz18mbf,
  author = {Sebastian Pütz and Jorge Santos Simón and Joachim Hertzberg},
  title = {{Move Base Flex}: A Highly Flexible Navigation Framework for Mobile Robots},
  booktitle = {2018 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS)},
  year = 2018,
  month = {October},
  url = {https://github.com/magazino/move_base_flex},
  note = {Software available at \url{https://github.com/magazino/move_base_flex}}
}

Please cite our paper if you use Move Base Flex in your research.

Concepts

We have created Move Base Flex for a larger target group besides the standard developers and users of move_base and 2D navigation based on costmaps, as well as addressed move_base's limitations. Since robot navigation can be separated into planning and controlling in many cases, even for outdoor scenarios without the benefits of flat terrain, we designed MBF based on abstract planner-, controller- and recovery behavior-execution classes. To accomplish this goal, we created abstract base classes for the nav core BaseLocalPlanner, BaseGlobalPlanner and RecoveryBehavior plugin interfaces, extending the API to provide a richer and more expressive interface without breaking the current move_base plugin API. The new abstract interfaces allow plugins to return valuable information in each execution cycle, e.g. why a valid plan or a velocity command could not be computed. This information is then passed to the external executive logic through MBF planning, navigation or recovering actions’ feedback and result. The planner, controller and recovery behavior execution is implemented in the abstract execution classes without binding the software implementation to 2D costmaps. In our framework, MoveBase is just a particular implementation of a navigation system: its execution classes implement the abstract ones, bind the system to the costmaps. Thereby, the system can easily be used for other approaches, e.g. navigation on meshes or 3D occupancy grid maps. However, we provide a SimpleNavigationServer class without a binding to costmaps.

Architecture

move_base_flex.png

Future Work

MBF is an ongoing project; some of the improvements we we have planned for the near future are:

  • Replace costmap_2d by grid_map in the mbf_costmap_nav server.

  • Add pause/resume interface for the controller, for example to recover from a bumper, or an emergency stop button hit
  • Plans with intermediate waypoints

But of course your are welcome to propose new fancy features and help make them a reality!

ROS API

Actions

Move Base Flex provides four actions which can be used by external executives to perform various navigation tasks and embed these into high-level applications. In the following the four actions get_path, exe_path, recovery and move_base are described in detail. The action definition files are stores here in the mbf_msgs package.

get_path

See mbf_msgs/GetPath.action

exe_path

See mbf_msgs/ExePath.action

recovery

See mbf_msgs/Recovery.action

move_base

See mbf_msgs/MoveBase.action

Topics

Subscribed Topics

odom (nav_msgs/Odometry)
  • Odometry information that gives the controllers the current speed of the robot. Change this topic by either remapping or by changing the parameter ~<name>/odom_topic.

Published Topics

cmd_vel (geometry_msgs/Twist)
  • A stream of velocity commands meant for execution by a mobile base.
~<name>/current_goal (geometry_msgs/PoseStamped)
  • Current goal pose, as sent to the path planner.

Services

~check_path_cost (mbf_msgs/CheckPath)
  • Check the accumulated cost of all cells traversed by a given path.
~check_point_cost (mbf_msgs/CheckPoint)
  • Check the cost of the costmap cell at a given point.
~check_pose_cost (mbf_msgs/CheckPose)
  • Check the accumulated cost of all cells covered by the robot footprint at a given pose.

Legacy API

In addition to this new API, we also provide the actions, services and topics provided by move_base for backwards-compatibility through the move_base legacy relay node.

Plugin Interfaces

mbf_abstract_core

See mbf_abstract_core for details.

mbf_costmap_core

See mbf_costmap_core for details.

mbf_abstract_nav

See mbf_abstract_nav for details.

mbf_costmap_nav

See mbf_costmap_nav for details.

mbf_simple_nav

See mbf_simple_nav for details.

Common Parameters

~<name>/planner_frequency (double, default: 0.0)

  • The rate in Hz at which to run the planning loop
~<name>/planner_patience (double, default: 5.0)
  • How long the planner will wait in seconds in an attempt to find a valid plan before giving up
~<name>/planner_max_retries (int, default: -1)
  • How many times we will recall the planner in an attempt to find a valid plan before giving up
~<name>/controller_frequency (double, default: 20.0)
  • The rate in Hz at which to run the control loop and send velocity commands to the base
~<name>/controller_patience (double, default: 5.0)
  • How long the controller will wait in seconds without receiving a valid control before giving up
~<name>/controller_max_retries (int, default: -1)
  • How many times we will recall the controller in an attempt to find a valid command before giving up
~<name>/recovery_enabled (bool, default: True)
  • Whether or not to enable the move_base_flex recovery behaviors to attempt to clear out space
~<name>/recovery_patience (double, default: 15.0)
  • How much time we allow recovery behaviors to complete before canceling (or stopping if cancel fails) them
~<name>/oscillation_timeout (double, default: 0.0)
  • How long in seconds to allow for oscillation before executing recovery behaviors
~<name>/oscillation_distance (double, default: 0.5)
  • How far in meters the robot must move to be considered not to be oscillating
~<name>/odom_topic (string, default: "odom")
  • Topic name for the odometry messages. Used to provide the current robot velocity to the controllers. If set empty, MBF will pass an uninitialized twist msg.

Note about max_retries and patience interaction:

All possible combinations are:

Patience

Retries

Effect

On Failure

> 0.0

> 0

keep retrying up to max_retries or patience runs out

MAX_RETRIES / PAT_EXCEEDED

0.0

> 0

keep retrying up to max_retries

MAX_RETRIES

> 0.0

0

one attempt; stop if patience runs out

NO_PLAN_FOUND / PAT_EXCEEDED

0.0

0

one attempt without time limit

NO_PLAN_FOUND

> 0.0

< 0

keep retrying until patience runs out

PAT_EXCEEDED

0.0

< 0

keep retrying forever

-

Note also that if patience runs out while planning, we will call planner's cancel method, interrupt it if it doesn't stop, and return PAT_EXCEEDED

Getting Started

Here you have a working minimal configuration for a turtlebot 3.

Tutorials

See move_base_flex/Tutorials.

Report a Bug

Use GitHub to report bugs or submit feature requests. [View active issues]

Wiki: move_base_flex (last edited 2022-04-25 01:15:23 by Jorge Santos)