Classes | Namespaces | Typedefs | Variables
abstract_navigation_server.h File Reference
#include <string>
#include <boost/shared_ptr.hpp>
#include <boost/thread/recursive_mutex.hpp>
#include <actionlib/server/action_server.h>
#include <dynamic_reconfigure/server.h>
#include <geometry_msgs/PoseStamped.h>
#include <mbf_utility/navigation_utility.h>
#include "mbf_abstract_nav/abstract_plugin_manager.h"
#include "mbf_abstract_nav/abstract_planner_execution.h"
#include "mbf_abstract_nav/abstract_controller_execution.h"
#include "mbf_abstract_nav/abstract_recovery_execution.h"
#include "mbf_abstract_nav/planner_action.h"
#include "mbf_abstract_nav/controller_action.h"
#include "mbf_abstract_nav/recovery_action.h"
#include "mbf_abstract_nav/move_base_action.h"
#include "mbf_abstract_nav/MoveBaseFlexConfig.h"
Include dependency graph for abstract_navigation_server.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  mbf_abstract_nav::AbstractNavigationServer
 The AbstractNavigationServer is the abstract base class for all navigation servers in move_base_flex and bundles the controller execution classes,the planner execution classes and the recovery execution classes. It provides the following action servers ActionServerGetPath -> callActionGetPath(), ActionServerExePath -> callActionExePath(), ActionServerRecovery -> callActionRecovery() and ActionServerMoveBase -> callActionMoveBase(). More...
 

Namespaces

 mbf_abstract_nav
 

Typedefs

typedef actionlib::ActionServer< mbf_msgs::ExePathAction > mbf_abstract_nav::ActionServerExePath
 ExePath action server. More...
 
typedef boost::shared_ptr< ActionServerExePath > mbf_abstract_nav::ActionServerExePathPtr
 
typedef actionlib::ActionServer< mbf_msgs::GetPathAction > mbf_abstract_nav::ActionServerGetPath
 GetPath action server. More...
 
typedef boost::shared_ptr< ActionServerGetPath > mbf_abstract_nav::ActionServerGetPathPtr
 
typedef actionlib::ActionServer< mbf_msgs::MoveBaseAction > mbf_abstract_nav::ActionServerMoveBase
 MoveBase action server. More...
 
typedef boost::shared_ptr< ActionServerMoveBase > mbf_abstract_nav::ActionServerMoveBasePtr
 
typedef actionlib::ActionServer< mbf_msgs::RecoveryAction > mbf_abstract_nav::ActionServerRecovery
 Recovery action server. More...
 
typedef boost::shared_ptr< ActionServerRecovery > mbf_abstract_nav::ActionServerRecoveryPtr
 
typedef boost::shared_ptr< dynamic_reconfigure::Server< mbf_abstract_nav::MoveBaseFlexConfig > > mbf_abstract_nav::DynamicReconfigureServer
 

Variables

const std::string mbf_abstract_nav::name_action_exe_path = "exe_path"
 ExePath action topic name. More...
 
const std::string mbf_abstract_nav::name_action_get_path = "get_path"
 GetPath action topic name. More...
 
const std::string mbf_abstract_nav::name_action_move_base = "move_base"
 MoveBase action topic name. More...
 
const std::string mbf_abstract_nav::name_action_recovery = "recovery"
 Recovery action topic name. More...
 


mbf_abstract_nav
Author(s): Sebastian Pütz
autogenerated on Mon Feb 28 2022 22:49:50