Move Base Flex Navigation Server

The Navigation Server class is the main class that manages the entire execution of the Move Base Flex Navigation Stack. This is a pure abstract class, so you need to derive your own class from this. Refer to the abstract_navigation_server.h file in the mbf_abstract_nav package for the nitty gritties, but read on for a brief overview of how it works.

Key Components of the MBF Navigation Server

The Navigation server has some key components:

TF stuff

The ROS TF2 library is also a integral part of the move_base_flex framework, which uses it to keep track of goal positions and frames. You don’t need to worry much about this, all you need to do is initialize a TF listener and pass it to the constructor, and move_base_flex handles the rest.

Action Servers and Variables

The move_base_flex exposes action servers that allow the user to provide goal commands, and also to track the execution of those goal commands. Again, this is entirely managed by move_base_flex, and we don’t need to write any code for the action server.

Plugin Managers

The navigation server has plugin managers that manages the planner, controller, and recovery behavior classes. The plugin manager ensures that the plugins load and initialize correctly, and also stores multiple planners, controllers and recovery behaviors. The code for plugin managers is already written, however, it needs to be provided with functions that load and initialize each plugin.

Plugin Loaders

This is not strictly a part of move_base_flex, but it is the recommended way you load the planner, controller and the recovery classes. That is how they have implemented it in their costmap_navigation package (which is just an implementation of move_base_flex that uses costmap2D and is backwards compatible with move_base plugins). Plugin loaders are a part of the ROS Pluginlib, which allows you to dynamically load and unload classes derived from a common base class. You are free to use whatever you like (heck, you can even just declare the classes in the class stack and pass its pointer too) in place of this method.

How does MBF Navigation Server run

This is a general overview of how the navigation server works.

How the navigation server constructor runs

The base class constructor does the following-

  • Initializes the planner, controller, and recovery behavior plugin managers. Most importantly, it gives the plugin managers the functions that load and initialize each plugin properly.
  • Initializes a bunch of TF variables, and also parameters like global and robot frames.
  • Initializes the action server variables.
  • Advertises some topics for publishing velocity commands and the current goal.
  • Initializes the action server with the variables, and also binds functions that are called whenever the action server gets a commands.

The constructor of the derived class would be implemented by you. You can put all the stuff you need to use to run the navigation server (like may be some extra parameters to load or topics you need to subscribe to). But, at the bare minimum, the constructor just has to do two things-

  • call the function initializeServerComponents(). This function has already been implemented, you just need to call it in your derived class constructor. This function essentially uses your plugin managers to load the planner, controller, and recovery behavior plugins.
  • call the function startActionServers(). This function also has already been implemented, you just need to call it in your derived class constructor. The job of this function is to start all the action servers which will then begin receiving goal commands.

initializeServerComponents() function

This function calls each plugin manager’s load function, which reads the planner names from the ros parameter server, and then calls the load and init function, which you have implemented in your navigation server. So, you need to implement these functions for initializeServerComponents to work-

  • loadPlannerPlugin
  • initializePlannerPlugin
  • loadControllerPlugin
  • initializeControllerPlugin
  • loadRecoveryPlugin
  • initializeRecoveryPlugin

An example code has been provided below which can also be seen in this file. Lets try to understand whatever is going on here.

mbf_abstract_core::AbstractPlanner::Ptr ExperimentalNavigationServer::loadPlannerPlugin(const std::string& planner_type)
{
  mbf_abstract_core::AbstractPlanner::Ptr planner_ptr = NULL;
  try
  {
    planner_ptr = boost::static_pointer_cast<mbf_abstract_core::AbstractPlanner>(
        planner_plugin_loader_.createInstance(planner_type));

    std::string planner_name = planner_plugin_loader_.getName(planner_type);
    ROS_DEBUG_STREAM("mbf_costmap_core-based planner plugin " << planner_name << " loaded.");
  }
  catch (const pluginlib::PluginlibException &ex_mbf_core)
  {
    ROS_DEBUG_STREAM("Failed to load the " << planner_type << " planner." << ex_mbf_core.what());
  }

  return planner_ptr;
}

bool ExperimentalNavigationServer::initializePlannerPlugin(const std::string& name,
                                                           const mbf_abstract_core::AbstractPlanner::Ptr& planner_ptr)
{
  std::cout << "Dummy Planner plugin initialized\n\n";
  return true;
}

As you can see from the return type, the job of this function is to load a planner plugin, and return its pointer. The main magic is happening in the statement- boost::static_pointer_cast<mbf_abstract_core::AbstractPlanner>( planner_plugin_loader_.createInstance(planner_type));

The createInstance function takes in a string planner_type (which is already loaded from the parameter server and passed onto the loadPlannerPlugin function), loads the requisite plugin, and returns its pointer. The rest of the code is just to give some info if the loading of the plugin fails. In the same way, you have to write the loadControllerPlugin and the loadRecoveryPlugin. Like said before, you absolutely don’t need to use ROS pluginlib to do this. You can statically allocate a planner object and return its pointer as well. But this is the recommended way to do it to maintain modularity of the codebase.

The initialize plugin functions like initializePlannerPlugin, initializeControllerPlugin, initializeRecoveryPlugin should have code that is required to properly initialize your planner, controller and recovery plugin. May be you need to set a few variables/parameters. May be you need to initialize a map representation. You can do all of that here. Return true or false depending on whether the initialization passed or failed.

If you don’t need to do that, you can just simply return true without doing anything. This is what is done in the example code shown above.

startActionServers() function

This function starts all the action servers. You don’t need to implement anything for it to work, just calling it in the constructor is enough.

Recap

In short, to make your navigation server class work, at the bare minimum, you need to implement the functions

  • loadPlannerPlugin
  • initializePlannerPlugin
  • loadControllerPlugin
  • initializeControllerPlugin
  • loadRecoveryPlugin
  • initializeRecoveryPlugin

and call the initializeServerComponents and startActionServer functions in the constructor. That is it, really. There are a lot of virtual functions in the abstract navigation server that you can override with your own implementations, if you wish to have more control over and modify the execution of the navigation server. Feel free to explore those functions in the abstract_navigation_server.h and abstract_navigation_server.cpp files, to see what they are doing.