Public Member Functions | Private Attributes | List of all members
mbf_simple_nav::SimpleNavigationServer Class Reference

The SimpleNavigationServer provides a simple navigation server, which does not bind a map representation to Move Base Flex. It combines the execution classes which use the mbf_abstract_core/AbstractController, mbf_abstract_core/AbstractPlanner and the mbf_abstract_core/AbstractRecovery base classes as plugin interfaces. More...

#include <simple_navigation_server.h>

Inheritance diagram for mbf_simple_nav::SimpleNavigationServer:
Inheritance graph
[legend]

Public Member Functions

virtual bool initializeControllerPlugin (const std::string &name, const mbf_abstract_core::AbstractController::Ptr &controller_ptr)
 Empty init method. Nothing to initialize. More...
 
virtual bool initializePlannerPlugin (const std::string &name, const mbf_abstract_core::AbstractPlanner::Ptr &planner_ptr)
 Empty init method. Nothing to initialize. More...
 
virtual bool initializeRecoveryPlugin (const std::string &name, const mbf_abstract_core::AbstractRecovery::Ptr &behavior_ptr)
 Pure virtual method, the derived class has to implement. Depending on the plugin base class, some plugins need to be initialized! More...
 
virtual mbf_abstract_core::AbstractController::Ptr loadControllerPlugin (const std::string &controller_type)
 Loads the plugin associated with the given controller type parameter. More...
 
virtual mbf_abstract_core::AbstractPlanner::Ptr loadPlannerPlugin (const std::string &planner_type)
 Loads the plugin associated with the given planner_type parameter. More...
 
virtual mbf_abstract_core::AbstractRecovery::Ptr loadRecoveryPlugin (const std::string &recovery_type)
 Loads a Recovery plugin associated with given recovery type parameter. More...
 
 SimpleNavigationServer (const TFPtr &tf_listener_ptr)
 Constructor. More...
 
virtual ~SimpleNavigationServer ()
 Destructor. More...
 
- Public Member Functions inherited from mbf_abstract_nav::AbstractNavigationServer
 AbstractNavigationServer (const TFPtr &tf_listener_ptr)
 
virtual void callActionExePath (ActionServerExePath::GoalHandle goal_handle)
 
virtual void callActionGetPath (ActionServerGetPath::GoalHandle goal_handle)
 
virtual void callActionMoveBase (ActionServerMoveBase::GoalHandle goal_handle)
 
virtual void callActionRecovery (ActionServerRecovery::GoalHandle goal_handle)
 
virtual void cancelActionExePath (ActionServerExePath::GoalHandle goal_handle)
 
virtual void cancelActionGetPath (ActionServerGetPath::GoalHandle goal_handle)
 
virtual void cancelActionMoveBase (ActionServerMoveBase::GoalHandle goal_handle)
 
virtual void cancelActionRecovery (ActionServerRecovery::GoalHandle goal_handle)
 
virtual void initializeServerComponents ()
 
virtual mbf_abstract_nav::AbstractControllerExecution::Ptr newControllerExecution (const std::string &plugin_name, const mbf_abstract_core::AbstractController::Ptr &plugin_ptr)
 
virtual mbf_abstract_nav::AbstractPlannerExecution::Ptr newPlannerExecution (const std::string &plugin_name, const mbf_abstract_core::AbstractPlanner::Ptr &plugin_ptr)
 
virtual mbf_abstract_nav::AbstractRecoveryExecution::Ptr newRecoveryExecution (const std::string &plugin_name, const mbf_abstract_core::AbstractRecovery::Ptr &plugin_ptr)
 
virtual void startActionServers ()
 
virtual void stop ()
 
virtual ~AbstractNavigationServer ()
 

Private Attributes

pluginlib::ClassLoader< mbf_abstract_core::AbstractControllercontroller_plugin_loader_
 
pluginlib::ClassLoader< mbf_abstract_core::AbstractPlannerplanner_plugin_loader_
 
pluginlib::ClassLoader< mbf_abstract_core::AbstractRecoveryrecovery_plugin_loader_
 

Additional Inherited Members

- Protected Member Functions inherited from mbf_abstract_nav::AbstractNavigationServer
virtual void reconfigure (mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level)
 
virtual void startDynamicReconfigureServer ()
 
bool transformPlanToGlobalFrame (std::vector< geometry_msgs::PoseStamped > &plan, std::vector< geometry_msgs::PoseStamped > &global_plan)
 
- Protected Attributes inherited from mbf_abstract_nav::AbstractNavigationServer
ActionServerExePathPtr action_server_exe_path_ptr_
 
ActionServerGetPathPtr action_server_get_path_ptr_
 
ActionServerMoveBasePtr action_server_move_base_ptr_
 
ActionServerRecoveryPtr action_server_recovery_ptr_
 
boost::mutex configuration_mutex_
 
ControllerAction controller_action_
 
AbstractPluginManager< mbf_abstract_core::AbstractControllercontroller_plugin_manager_
 
mbf_abstract_nav::MoveBaseFlexConfig default_config_
 
DynamicReconfigureServer dsrv_
 
std::string global_frame_
 
ros::Publisher goal_pub_
 
mbf_abstract_nav::MoveBaseFlexConfig last_config_
 
MoveBaseAction move_base_action_
 
PlannerAction planner_action_
 
AbstractPluginManager< mbf_abstract_core::AbstractPlannerplanner_plugin_manager_
 
ros::NodeHandle private_nh_
 
RecoveryAction recovery_action_
 
AbstractPluginManager< mbf_abstract_core::AbstractRecoveryrecovery_plugin_manager_
 
std::string robot_frame_
 
mbf_utility::RobotInformation robot_info_
 
bool setup_reconfigure_
 
const TFPtr tf_listener_ptr_
 
ros::Duration tf_timeout_
 
ros::Publisher vel_pub_
 

Detailed Description

The SimpleNavigationServer provides a simple navigation server, which does not bind a map representation to Move Base Flex. It combines the execution classes which use the mbf_abstract_core/AbstractController, mbf_abstract_core/AbstractPlanner and the mbf_abstract_core/AbstractRecovery base classes as plugin interfaces.

Definition at line 63 of file simple_navigation_server.h.

Constructor & Destructor Documentation

◆ SimpleNavigationServer()

mbf_simple_nav::SimpleNavigationServer::SimpleNavigationServer ( const TFPtr tf_listener_ptr)

Constructor.

Parameters
tf_listener_ptrShared pointer to a common TransformListener

Definition at line 46 of file simple_navigation_server.cpp.

◆ ~SimpleNavigationServer()

mbf_simple_nav::SimpleNavigationServer::~SimpleNavigationServer ( )
virtual

Destructor.

Definition at line 138 of file simple_navigation_server.cpp.

Member Function Documentation

◆ initializeControllerPlugin()

bool mbf_simple_nav::SimpleNavigationServer::initializeControllerPlugin ( const std::string &  name,
const mbf_abstract_core::AbstractController::Ptr controller_ptr 
)
virtual

Empty init method. Nothing to initialize.

Parameters
nameThe name of the controller
controller_ptrpointer to the controller object which corresponds to the name param
Returns
true always

Implements mbf_abstract_nav::AbstractNavigationServer.

Definition at line 105 of file simple_navigation_server.cpp.

◆ initializePlannerPlugin()

bool mbf_simple_nav::SimpleNavigationServer::initializePlannerPlugin ( const std::string &  name,
const mbf_abstract_core::AbstractPlanner::Ptr planner_ptr 
)
virtual

Empty init method. Nothing to initialize.

Parameters
nameThe name of the planner
planner_ptrpointer to the planner object which corresponds to the name param
Returns
true always

Implements mbf_abstract_nav::AbstractNavigationServer.

Definition at line 77 of file simple_navigation_server.cpp.

◆ initializeRecoveryPlugin()

bool mbf_simple_nav::SimpleNavigationServer::initializeRecoveryPlugin ( const std::string &  name,
const mbf_abstract_core::AbstractRecovery::Ptr behavior_ptr 
)
virtual

Pure virtual method, the derived class has to implement. Depending on the plugin base class, some plugins need to be initialized!

Parameters
nameThe name of the recovery behavior
behavior_ptrpointer to the recovery behavior object which corresponds to the name param
Returns
true always

Implements mbf_abstract_nav::AbstractNavigationServer.

Definition at line 130 of file simple_navigation_server.cpp.

◆ loadControllerPlugin()

mbf_abstract_core::AbstractController::Ptr mbf_simple_nav::SimpleNavigationServer::loadControllerPlugin ( const std::string &  controller_type)
virtual

Loads the plugin associated with the given controller type parameter.

Parameters
controller_typeThe type of the controller plugin
Returns
A shared pointer to a new loaded controller, if the controller plugin was loaded successfully, an empty pointer otherwise.

Implements mbf_abstract_nav::AbstractNavigationServer.

Definition at line 86 of file simple_navigation_server.cpp.

◆ loadPlannerPlugin()

mbf_abstract_core::AbstractPlanner::Ptr mbf_simple_nav::SimpleNavigationServer::loadPlannerPlugin ( const std::string &  planner_type)
virtual

Loads the plugin associated with the given planner_type parameter.

Parameters
planner_typeThe type of the planner plugin to load.
Returns
true, if the local planner plugin was successfully loaded.

Implements mbf_abstract_nav::AbstractNavigationServer.

Definition at line 59 of file simple_navigation_server.cpp.

◆ loadRecoveryPlugin()

mbf_abstract_core::AbstractRecovery::Ptr mbf_simple_nav::SimpleNavigationServer::loadRecoveryPlugin ( const std::string &  recovery_type)
virtual

Loads a Recovery plugin associated with given recovery type parameter.

Parameters
recovery_nameThe name of the Recovery plugin
Returns
A shared pointer to a Recovery plugin, if the plugin was loaded successfully, an empty pointer otherwise.

Implements mbf_abstract_nav::AbstractNavigationServer.

Definition at line 112 of file simple_navigation_server.cpp.

Member Data Documentation

◆ controller_plugin_loader_

pluginlib::ClassLoader<mbf_abstract_core::AbstractController> mbf_simple_nav::SimpleNavigationServer::controller_plugin_loader_
private

Definition at line 136 of file simple_navigation_server.h.

◆ planner_plugin_loader_

pluginlib::ClassLoader<mbf_abstract_core::AbstractPlanner> mbf_simple_nav::SimpleNavigationServer::planner_plugin_loader_
private

Definition at line 135 of file simple_navigation_server.h.

◆ recovery_plugin_loader_

pluginlib::ClassLoader<mbf_abstract_core::AbstractRecovery> mbf_simple_nav::SimpleNavigationServer::recovery_plugin_loader_
private

Definition at line 137 of file simple_navigation_server.h.


The documentation for this class was generated from the following files:


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