Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
mbf_abstract_nav::AbstractNavigationServer Class Referenceabstract

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...

#include <abstract_navigation_server.h>

Public Member Functions

 AbstractNavigationServer (const TFPtr &tf_listener_ptr)
 Constructor, reads all parameters and initializes all action servers and creates the plugin instances. Parameters are the concrete implementations of the abstract classes. More...
 
virtual void callActionExePath (ActionServerExePath::GoalHandle goal_handle)
 ExePath action execution method. This method will be called if the action server receives a goal. More...
 
virtual void callActionGetPath (ActionServerGetPath::GoalHandle goal_handle)
 GetPath action execution method. This method will be called if the action server receives a goal. More...
 
virtual void callActionMoveBase (ActionServerMoveBase::GoalHandle goal_handle)
 MoveBase action execution method. This method will be called if the action server receives a goal. More...
 
virtual void callActionRecovery (ActionServerRecovery::GoalHandle goal_handle)
 Recovery action execution method. This method will be called if the action server receives a goal. More...
 
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 bool initializeControllerPlugin (const std::string &name, const mbf_abstract_core::AbstractController::Ptr &controller_ptr)=0
 Pure virtual method, the derived class has to implement. Depending on the plugin base class, some plugins need to be initialized! More...
 
virtual bool initializePlannerPlugin (const std::string &name, const mbf_abstract_core::AbstractPlanner::Ptr &planner_ptr)=0
 Pure virtual method, the derived class has to implement. Depending on the plugin base class, some plugins need to be initialized! More...
 
virtual bool initializeRecoveryPlugin (const std::string &name, const mbf_abstract_core::AbstractRecovery::Ptr &behavior_ptr)=0
 Pure virtual method, the derived class has to implement. Depending on the plugin base class, some plugins need to be initialized! More...
 
virtual void initializeServerComponents ()
 initializes all server components. Initializing the plugins of the Planner, the Controller, and the Recovery Behavior. More...
 
virtual mbf_abstract_core::AbstractController::Ptr loadControllerPlugin (const std::string &controller_type)=0
 Loads the plugin associated with the given controller type parameter. More...
 
virtual mbf_abstract_core::AbstractPlanner::Ptr loadPlannerPlugin (const std::string &planner_type)=0
 Loads the plugin associated with the given planner_type parameter. More...
 
virtual mbf_abstract_core::AbstractRecovery::Ptr loadRecoveryPlugin (const std::string &recovery_type)=0
 Loads a Recovery plugin associated with given recovery type parameter. More...
 
virtual mbf_abstract_nav::AbstractControllerExecution::Ptr newControllerExecution (const std::string &plugin_name, const mbf_abstract_core::AbstractController::Ptr &plugin_ptr)
 Create a new abstract controller execution. More...
 
virtual mbf_abstract_nav::AbstractPlannerExecution::Ptr newPlannerExecution (const std::string &plugin_name, const mbf_abstract_core::AbstractPlanner::Ptr &plugin_ptr)
 Create a new abstract planner execution. More...
 
virtual mbf_abstract_nav::AbstractRecoveryExecution::Ptr newRecoveryExecution (const std::string &plugin_name, const mbf_abstract_core::AbstractRecovery::Ptr &plugin_ptr)
 Create a new abstract recovery behavior execution. More...
 
virtual void startActionServers ()
 starts all action server. More...
 
virtual void stop ()
 
virtual ~AbstractNavigationServer ()
 Destructor. More...
 

Protected Member Functions

virtual void reconfigure (mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level)
 Reconfiguration method called by dynamic reconfigure. More...
 
virtual void startDynamicReconfigureServer ()
 Start a dynamic reconfigure server. This must be called only if the extending doesn't create its own. More...
 
bool transformPlanToGlobalFrame (std::vector< geometry_msgs::PoseStamped > &plan, std::vector< geometry_msgs::PoseStamped > &global_plan)
 Transforms a plan to the global frame (global_frame_) coord system. More...
 

Protected Attributes

ActionServerExePathPtr action_server_exe_path_ptr_
 shared pointer to the ExePath action server More...
 
ActionServerGetPathPtr action_server_get_path_ptr_
 shared pointer to the GetPath action server More...
 
ActionServerMoveBasePtr action_server_move_base_ptr_
 shared pointer to the MoveBase action server More...
 
ActionServerRecoveryPtr action_server_recovery_ptr_
 shared pointer to the Recovery action server More...
 
boost::mutex configuration_mutex_
 configuration mutex for derived classes and other threads. More...
 
ControllerAction controller_action_
 
AbstractPluginManager< mbf_abstract_core::AbstractControllercontroller_plugin_manager_
 
mbf_abstract_nav::MoveBaseFlexConfig default_config_
 the default parameter configuration save More...
 
DynamicReconfigureServer dsrv_
 dynamic reconfigure server More...
 
std::string global_frame_
 the global frame, in which the robot is moving More...
 
ros::Publisher goal_pub_
 current_goal publisher for all controller execution objects More...
 
mbf_abstract_nav::MoveBaseFlexConfig last_config_
 last configuration save More...
 
MoveBaseAction move_base_action_
 
PlannerAction planner_action_
 
AbstractPluginManager< mbf_abstract_core::AbstractPlannerplanner_plugin_manager_
 
ros::NodeHandle private_nh_
 Private node handle. More...
 
RecoveryAction recovery_action_
 
AbstractPluginManager< mbf_abstract_core::AbstractRecoveryrecovery_plugin_manager_
 
std::string robot_frame_
 the robot frame, to get the current robot pose in the global_frame_ More...
 
mbf_utility::RobotInformation robot_info_
 current robot state More...
 
bool setup_reconfigure_
 true, if the dynamic reconfigure has been setup. More...
 
const TFPtr tf_listener_ptr_
 shared pointer to the common TransformListener More...
 
ros::Duration tf_timeout_
 timeout after tf returns without a result More...
 
ros::Publisher vel_pub_
 cmd_vel publisher for all controller execution objects More...
 

Detailed Description

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().

Definition at line 118 of file abstract_navigation_server.h.

Constructor & Destructor Documentation

◆ AbstractNavigationServer()

mbf_abstract_nav::AbstractNavigationServer::AbstractNavigationServer ( const TFPtr tf_listener_ptr)

Constructor, reads all parameters and initializes all action servers and creates the plugin instances. Parameters are the concrete implementations of the abstract classes.

Parameters
tf_listener_ptrshared pointer to the common TransformListener buffering transformations

Definition at line 48 of file abstract_navigation_server.cpp.

◆ ~AbstractNavigationServer()

mbf_abstract_nav::AbstractNavigationServer::~AbstractNavigationServer ( )
virtual

Destructor.

Definition at line 119 of file abstract_navigation_server.cpp.

Member Function Documentation

◆ callActionExePath()

void mbf_abstract_nav::AbstractNavigationServer::callActionExePath ( ActionServerExePath::GoalHandle  goal_handle)
virtual

ExePath action execution method. This method will be called if the action server receives a goal.

Parameters
goalSimpleActionServer goal containing all necessary parameters for the action execution. See the action definitions in mbf_msgs.

Definition at line 183 of file abstract_navigation_server.cpp.

◆ callActionGetPath()

void mbf_abstract_nav::AbstractNavigationServer::callActionGetPath ( ActionServerGetPath::GoalHandle  goal_handle)
virtual

GetPath action execution method. This method will be called if the action server receives a goal.

Parameters
goalSimpleActionServer goal containing all necessary parameters for the action execution. See the action definitions in mbf_msgs.

Definition at line 124 of file abstract_navigation_server.cpp.

◆ callActionMoveBase()

void mbf_abstract_nav::AbstractNavigationServer::callActionMoveBase ( ActionServerMoveBase::GoalHandle  goal_handle)
virtual

MoveBase action execution method. This method will be called if the action server receives a goal.

Parameters
goalSimpleActionServer goal containing all necessary parameters for the action execution. See the action definitions in mbf_msgs.

Definition at line 299 of file abstract_navigation_server.cpp.

◆ callActionRecovery()

void mbf_abstract_nav::AbstractNavigationServer::callActionRecovery ( ActionServerRecovery::GoalHandle  goal_handle)
virtual

Recovery action execution method. This method will be called if the action server receives a goal.

Parameters
goalSimpleActionServer goal containing all necessary parameters for the action execution. See the action definitions in mbf_msgs.

Definition at line 241 of file abstract_navigation_server.cpp.

◆ cancelActionExePath()

void mbf_abstract_nav::AbstractNavigationServer::cancelActionExePath ( ActionServerExePath::GoalHandle  goal_handle)
virtual

Definition at line 235 of file abstract_navigation_server.cpp.

◆ cancelActionGetPath()

void mbf_abstract_nav::AbstractNavigationServer::cancelActionGetPath ( ActionServerGetPath::GoalHandle  goal_handle)
virtual

Definition at line 177 of file abstract_navigation_server.cpp.

◆ cancelActionMoveBase()

void mbf_abstract_nav::AbstractNavigationServer::cancelActionMoveBase ( ActionServerMoveBase::GoalHandle  goal_handle)
virtual

Definition at line 305 of file abstract_navigation_server.cpp.

◆ cancelActionRecovery()

void mbf_abstract_nav::AbstractNavigationServer::cancelActionRecovery ( ActionServerRecovery::GoalHandle  goal_handle)
virtual

Definition at line 293 of file abstract_navigation_server.cpp.

◆ initializeControllerPlugin()

virtual bool mbf_abstract_nav::AbstractNavigationServer::initializeControllerPlugin ( const std::string &  name,
const mbf_abstract_core::AbstractController::Ptr controller_ptr 
)
pure 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 controller
controller_ptrpointer to the controller object which corresponds to the name param
Returns
true if init succeeded, false otherwise

◆ initializePlannerPlugin()

virtual bool mbf_abstract_nav::AbstractNavigationServer::initializePlannerPlugin ( const std::string &  name,
const mbf_abstract_core::AbstractPlanner::Ptr planner_ptr 
)
pure 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 planner
planner_ptrpointer to the planner object which corresponds to the name param
Returns
true if init succeeded, false otherwise

◆ initializeRecoveryPlugin()

virtual bool mbf_abstract_nav::AbstractNavigationServer::initializeRecoveryPlugin ( const std::string &  name,
const mbf_abstract_core::AbstractRecovery::Ptr behavior_ptr 
)
pure 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 if init succeeded, false otherwise

◆ initializeServerComponents()

void mbf_abstract_nav::AbstractNavigationServer::initializeServerComponents ( )
virtual

initializes all server components. Initializing the plugins of the Planner, the Controller, and the Recovery Behavior.

Definition at line 112 of file abstract_navigation_server.cpp.

◆ loadControllerPlugin()

virtual mbf_abstract_core::AbstractController::Ptr mbf_abstract_nav::AbstractNavigationServer::loadControllerPlugin ( const std::string &  controller_type)
pure 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.

◆ loadPlannerPlugin()

virtual mbf_abstract_core::AbstractPlanner::Ptr mbf_abstract_nav::AbstractNavigationServer::loadPlannerPlugin ( const std::string &  planner_type)
pure virtual

Loads the plugin associated with the given planner_type parameter.

Parameters
planner_typeThe type of the planner plugin to load.
Returns
Pointer to the loaded plugin

◆ loadRecoveryPlugin()

virtual mbf_abstract_core::AbstractRecovery::Ptr mbf_abstract_nav::AbstractNavigationServer::loadRecoveryPlugin ( const std::string &  recovery_type)
pure 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.

◆ newControllerExecution()

mbf_abstract_nav::AbstractControllerExecution::Ptr mbf_abstract_nav::AbstractNavigationServer::newControllerExecution ( const std::string &  plugin_name,
const mbf_abstract_core::AbstractController::Ptr plugin_ptr 
)
virtual

Create a new abstract controller execution.

Parameters
plugin_nameName of the controller to use.
plugin_ptrShared pointer to the plugin to use.
Returns
Shared pointer to a new ControllerExecution.

Definition at line 319 of file abstract_navigation_server.cpp.

◆ newPlannerExecution()

mbf_abstract_nav::AbstractPlannerExecution::Ptr mbf_abstract_nav::AbstractNavigationServer::newPlannerExecution ( const std::string &  plugin_name,
const mbf_abstract_core::AbstractPlanner::Ptr plugin_ptr 
)
virtual

Create a new abstract planner execution.

Parameters
plugin_nameName of the planner to use.
plugin_ptrShared pointer to the plugin to use.
Returns
Shared pointer to a new PlannerExecution.

Definition at line 312 of file abstract_navigation_server.cpp.

◆ newRecoveryExecution()

mbf_abstract_nav::AbstractRecoveryExecution::Ptr mbf_abstract_nav::AbstractNavigationServer::newRecoveryExecution ( const std::string &  plugin_name,
const mbf_abstract_core::AbstractRecovery::Ptr plugin_ptr 
)
virtual

Create a new abstract recovery behavior execution.

Parameters
plugin_nameName of the recovery behavior to run.
plugin_ptrShared pointer to the plugin to use
Returns
Shared pointer to a new RecoveryExecution.

Definition at line 327 of file abstract_navigation_server.cpp.

◆ reconfigure()

void mbf_abstract_nav::AbstractNavigationServer::reconfigure ( mbf_abstract_nav::MoveBaseFlexConfig &  config,
uint32_t  level 
)
protectedvirtual

Reconfiguration method called by dynamic reconfigure.

Parameters
configConfiguration parameters. See the MoveBaseFlexConfig definition.
levelbit mask, which parameters are set.

Definition at line 350 of file abstract_navigation_server.cpp.

◆ startActionServers()

void mbf_abstract_nav::AbstractNavigationServer::startActionServers ( )
virtual

starts all action server.

Definition at line 335 of file abstract_navigation_server.cpp.

◆ startDynamicReconfigureServer()

void mbf_abstract_nav::AbstractNavigationServer::startDynamicReconfigureServer ( )
protectedvirtual

Start a dynamic reconfigure server. This must be called only if the extending doesn't create its own.

Definition at line 343 of file abstract_navigation_server.cpp.

◆ stop()

void mbf_abstract_nav::AbstractNavigationServer::stop ( )
virtual

Definition at line 376 of file abstract_navigation_server.cpp.

◆ transformPlanToGlobalFrame()

bool mbf_abstract_nav::AbstractNavigationServer::transformPlanToGlobalFrame ( std::vector< geometry_msgs::PoseStamped > &  plan,
std::vector< geometry_msgs::PoseStamped > &  global_plan 
)
protected

Transforms a plan to the global frame (global_frame_) coord system.

Parameters
planInput plan to be transformed.
global_planOutput plan, which is then transformed to the global frame.
Returns
true, if the transformation succeeded, false otherwise

Member Data Documentation

◆ action_server_exe_path_ptr_

ActionServerExePathPtr mbf_abstract_nav::AbstractNavigationServer::action_server_exe_path_ptr_
protected

shared pointer to the ExePath action server

Definition at line 307 of file abstract_navigation_server.h.

◆ action_server_get_path_ptr_

ActionServerGetPathPtr mbf_abstract_nav::AbstractNavigationServer::action_server_get_path_ptr_
protected

shared pointer to the GetPath action server

Definition at line 310 of file abstract_navigation_server.h.

◆ action_server_move_base_ptr_

ActionServerMoveBasePtr mbf_abstract_nav::AbstractNavigationServer::action_server_move_base_ptr_
protected

shared pointer to the MoveBase action server

Definition at line 313 of file abstract_navigation_server.h.

◆ action_server_recovery_ptr_

ActionServerRecoveryPtr mbf_abstract_nav::AbstractNavigationServer::action_server_recovery_ptr_
protected

shared pointer to the Recovery action server

Definition at line 304 of file abstract_navigation_server.h.

◆ configuration_mutex_

boost::mutex mbf_abstract_nav::AbstractNavigationServer::configuration_mutex_
protected

configuration mutex for derived classes and other threads.

Definition at line 319 of file abstract_navigation_server.h.

◆ controller_action_

ControllerAction mbf_abstract_nav::AbstractNavigationServer::controller_action_
protected

Definition at line 351 of file abstract_navigation_server.h.

◆ controller_plugin_manager_

AbstractPluginManager<mbf_abstract_core::AbstractController> mbf_abstract_nav::AbstractNavigationServer::controller_plugin_manager_
protected

Definition at line 300 of file abstract_navigation_server.h.

◆ default_config_

mbf_abstract_nav::MoveBaseFlexConfig mbf_abstract_nav::AbstractNavigationServer::default_config_
protected

the default parameter configuration save

Definition at line 325 of file abstract_navigation_server.h.

◆ dsrv_

DynamicReconfigureServer mbf_abstract_nav::AbstractNavigationServer::dsrv_
protected

dynamic reconfigure server

Definition at line 316 of file abstract_navigation_server.h.

◆ global_frame_

std::string mbf_abstract_nav::AbstractNavigationServer::global_frame_
protected

the global frame, in which the robot is moving

Definition at line 334 of file abstract_navigation_server.h.

◆ goal_pub_

ros::Publisher mbf_abstract_nav::AbstractNavigationServer::goal_pub_
protected

current_goal publisher for all controller execution objects

Definition at line 346 of file abstract_navigation_server.h.

◆ last_config_

mbf_abstract_nav::MoveBaseFlexConfig mbf_abstract_nav::AbstractNavigationServer::last_config_
protected

last configuration save

Definition at line 322 of file abstract_navigation_server.h.

◆ move_base_action_

MoveBaseAction mbf_abstract_nav::AbstractNavigationServer::move_base_action_
protected

Definition at line 354 of file abstract_navigation_server.h.

◆ planner_action_

PlannerAction mbf_abstract_nav::AbstractNavigationServer::planner_action_
protected

Definition at line 352 of file abstract_navigation_server.h.

◆ planner_plugin_manager_

AbstractPluginManager<mbf_abstract_core::AbstractPlanner> mbf_abstract_nav::AbstractNavigationServer::planner_plugin_manager_
protected

Definition at line 299 of file abstract_navigation_server.h.

◆ private_nh_

ros::NodeHandle mbf_abstract_nav::AbstractNavigationServer::private_nh_
protected

Private node handle.

Definition at line 297 of file abstract_navigation_server.h.

◆ recovery_action_

RecoveryAction mbf_abstract_nav::AbstractNavigationServer::recovery_action_
protected

Definition at line 353 of file abstract_navigation_server.h.

◆ recovery_plugin_manager_

AbstractPluginManager<mbf_abstract_core::AbstractRecovery> mbf_abstract_nav::AbstractNavigationServer::recovery_plugin_manager_
protected

Definition at line 301 of file abstract_navigation_server.h.

◆ robot_frame_

std::string mbf_abstract_nav::AbstractNavigationServer::robot_frame_
protected

the robot frame, to get the current robot pose in the global_frame_

Definition at line 331 of file abstract_navigation_server.h.

◆ robot_info_

mbf_utility::RobotInformation mbf_abstract_nav::AbstractNavigationServer::robot_info_
protected

current robot state

Definition at line 349 of file abstract_navigation_server.h.

◆ setup_reconfigure_

bool mbf_abstract_nav::AbstractNavigationServer::setup_reconfigure_
protected

true, if the dynamic reconfigure has been setup.

Definition at line 328 of file abstract_navigation_server.h.

◆ tf_listener_ptr_

const TFPtr mbf_abstract_nav::AbstractNavigationServer::tf_listener_ptr_
protected

shared pointer to the common TransformListener

Definition at line 340 of file abstract_navigation_server.h.

◆ tf_timeout_

ros::Duration mbf_abstract_nav::AbstractNavigationServer::tf_timeout_
protected

timeout after tf returns without a result

Definition at line 337 of file abstract_navigation_server.h.

◆ vel_pub_

ros::Publisher mbf_abstract_nav::AbstractNavigationServer::vel_pub_
protected

cmd_vel publisher for all controller execution objects

Definition at line 343 of file abstract_navigation_server.h.


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


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