Public Member Functions | Protected Member Functions | Protected Attributes
mbf_abstract_nav::AbstractNavigationServer Class Reference

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>

List of all members.

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.
virtual void callActionExePath (ActionServerExePath::GoalHandle goal_handle)
 ExePath action execution method. This method will be called if the action server receives a goal.
virtual void callActionGetPath (ActionServerGetPath::GoalHandle goal_handle)
 GetPath action execution method. This method will be called if the action server receives a goal.
virtual void callActionMoveBase (ActionServerMoveBase::GoalHandle goal_handle)
 MoveBase action execution method. This method will be called if the action server receives a goal.
virtual void callActionRecovery (ActionServerRecovery::GoalHandle goal_handle)
 Recovery action execution method. This method will be called if the action server receives a goal.
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)
bool getRobotPose (geometry_msgs::PoseStamped &robot_pose)
 Computes the current robot pose (robot_frame_) in the global frame (global_frame_).
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!
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!
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!
virtual void initializeServerComponents ()
 initializes all server components. Initializing the plugins of the Planner, the Controller, and the Recovery Behavior.
virtual
mbf_abstract_core::AbstractController::Ptr 
loadControllerPlugin (const std::string &controller_type)=0
 Loads the plugin associated with the given controller type parameter.
virtual
mbf_abstract_core::AbstractPlanner::Ptr 
loadPlannerPlugin (const std::string &planner_type)=0
 Loads the plugin associated with the given planner_type parameter.
virtual
mbf_abstract_core::AbstractRecovery::Ptr 
loadRecoveryPlugin (const std::string &recovery_type)=0
 Loads a Recovery plugin associated with given recovery type parameter.
virtual
mbf_abstract_nav::AbstractControllerExecution::Ptr 
newControllerExecution (const std::string plugin_name, const mbf_abstract_core::AbstractController::Ptr plugin_ptr)
 shared pointer to a new ControllerExecution
virtual
mbf_abstract_nav::AbstractPlannerExecution::Ptr 
newPlannerExecution (const std::string plugin_name, const mbf_abstract_core::AbstractPlanner::Ptr plugin_ptr)
 shared pointer to a new PlannerExecution
virtual
mbf_abstract_nav::AbstractRecoveryExecution::Ptr 
newRecoveryExecution (const std::string plugin_name, const mbf_abstract_core::AbstractRecovery::Ptr plugin_ptr)
 shared pointer to a new RecoveryExecution
virtual void startActionServers ()
 starts all action server.
virtual void stop ()
virtual ~AbstractNavigationServer ()
 Destructor.

Protected Member Functions

virtual void reconfigure (mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level)
 Reconfiguration method called by dynamic reconfigure.
virtual void startDynamicReconfigureServer ()
 Start a dynamic reconfigure server. This must be called only if the extending doesn't create its own.
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.

Protected Attributes

ActionServerExePathPtr action_server_exe_path_ptr_
 shared pointer to the ExePath action server
ActionServerGetPathPtr action_server_get_path_ptr_
 shared pointer to the GetPath action server
ActionServerMoveBasePtr action_server_move_base_ptr_
 shared pointer to the MoveBase action server
ActionServerRecoveryPtr action_server_recovery_ptr_
 shared pointer to the Recovery action server
bool clearing_rotation_allowed_
 true, if clearing rotate is allowed.
boost::mutex configuration_mutex_
 configuration mutex for derived classes and other threads.
ControllerAction controller_action_
AbstractPluginManager
< mbf_abstract_core::AbstractController
controller_plugin_manager_
mbf_abstract_nav::MoveBaseFlexConfig default_config_
 the default parameter configuration save
DynamicReconfigureServer dsrv_
 dynamic reconfigure server
std::string global_frame_
 the global frame, in which the robot is moving
geometry_msgs::PoseStamped goal_pose_
 current goal pose; used to compute remaining distance and angle
ros::Publisher goal_pub_
 current_goal publisher for all controller execution objects
mbf_abstract_nav::MoveBaseFlexConfig last_config_
 last configuration save
MoveBaseAction move_base_action_
double oscillation_distance_
 minimal move distance to not detect an oscillation
ros::Duration oscillation_timeout_
 timeout after a oscillation is detected
PlannerAction planner_action_
AbstractPluginManager
< mbf_abstract_core::AbstractPlanner
planner_plugin_manager_
ros::NodeHandle private_nh_
 Private node handle.
RecoveryAction recovery_action_
bool recovery_enabled_
 true, if recovery behavior for the MoveBase action is enabled.
AbstractPluginManager
< mbf_abstract_core::AbstractRecovery
recovery_plugin_manager_
std::string robot_frame_
 the robot frame, to get the current robot pose in the global_frame_
RobotInformation robot_info_
geometry_msgs::PoseStamped robot_pose_
 current robot pose; moving controller is responsible to update it by calling getRobotPose
bool setup_reconfigure_
 true, if the dynamic reconfigure has been setup.
const TFPtr tf_listener_ptr_
 shared pointer to the common TransformListener
ros::Duration tf_timeout_
 timeout after tf returns without a result
ros::Publisher vel_pub_
 cmd_vel publisher for all controller execution objects

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 119 of file abstract_navigation_server.h.


Constructor & Destructor Documentation

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
planning_ptrshared pointer to an object of the concrete derived implementation of the AbstractPlannerExecution
moving_ptrshared pointer to an object of the concrete derived implementation of the AbstractControllerExecution
recovery_ptrshared pointer to an object of the concrete derived implementation of the AbstractRecoveryExecution

Definition at line 48 of file abstract_navigation_server.cpp.

Destructor.

Definition at line 125 of file abstract_navigation_server.cpp.


Member Function Documentation

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 189 of file abstract_navigation_server.cpp.

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 130 of file abstract_navigation_server.cpp.

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 305 of file abstract_navigation_server.cpp.

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 247 of file abstract_navigation_server.cpp.

Definition at line 241 of file abstract_navigation_server.cpp.

Definition at line 183 of file abstract_navigation_server.cpp.

Definition at line 311 of file abstract_navigation_server.cpp.

Definition at line 299 of file abstract_navigation_server.cpp.

bool mbf_abstract_nav::AbstractNavigationServer::getRobotPose ( geometry_msgs::PoseStamped &  robot_pose)

Computes the current robot pose (robot_frame_) in the global frame (global_frame_).

Parameters:
robot_poseReference to the robot_pose message object to be filled.
Returns:
true, if the current robot pose could be computed, false otherwise.
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
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
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

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

Definition at line 118 of file abstract_navigation_server.cpp.

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.

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

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.

shared pointer to a new ControllerExecution

Definition at line 326 of file abstract_navigation_server.cpp.

shared pointer to a new PlannerExecution

Definition at line 317 of file abstract_navigation_server.cpp.

shared pointer to a new RecoveryExecution

Definition at line 334 of file abstract_navigation_server.cpp.

void mbf_abstract_nav::AbstractNavigationServer::reconfigure ( mbf_abstract_nav::MoveBaseFlexConfig &  config,
uint32_t  level 
) [protected, virtual]

Reconfiguration method called by dynamic reconfigure.

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

Definition at line 358 of file abstract_navigation_server.cpp.

starts all action server.

Definition at line 343 of file abstract_navigation_server.cpp.

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

Definition at line 351 of file abstract_navigation_server.cpp.

Definition at line 384 of file abstract_navigation_server.cpp.

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

shared pointer to the ExePath action server

Definition at line 302 of file abstract_navigation_server.h.

shared pointer to the GetPath action server

Definition at line 305 of file abstract_navigation_server.h.

shared pointer to the MoveBase action server

Definition at line 308 of file abstract_navigation_server.h.

shared pointer to the Recovery action server

Definition at line 299 of file abstract_navigation_server.h.

true, if clearing rotate is allowed.

Definition at line 353 of file abstract_navigation_server.h.

configuration mutex for derived classes and other threads.

Definition at line 314 of file abstract_navigation_server.h.

Definition at line 363 of file abstract_navigation_server.h.

Definition at line 295 of file abstract_navigation_server.h.

mbf_abstract_nav::MoveBaseFlexConfig mbf_abstract_nav::AbstractNavigationServer::default_config_ [protected]

the default parameter configuration save

Definition at line 320 of file abstract_navigation_server.h.

dynamic reconfigure server

Definition at line 311 of file abstract_navigation_server.h.

the global frame, in which the robot is moving

Definition at line 329 of file abstract_navigation_server.h.

geometry_msgs::PoseStamped mbf_abstract_nav::AbstractNavigationServer::goal_pose_ [protected]

current goal pose; used to compute remaining distance and angle

Definition at line 341 of file abstract_navigation_server.h.

current_goal publisher for all controller execution objects

Definition at line 359 of file abstract_navigation_server.h.

mbf_abstract_nav::MoveBaseFlexConfig mbf_abstract_nav::AbstractNavigationServer::last_config_ [protected]

last configuration save

Definition at line 317 of file abstract_navigation_server.h.

Definition at line 366 of file abstract_navigation_server.h.

minimal move distance to not detect an oscillation

Definition at line 347 of file abstract_navigation_server.h.

timeout after a oscillation is detected

Definition at line 344 of file abstract_navigation_server.h.

Definition at line 364 of file abstract_navigation_server.h.

Definition at line 294 of file abstract_navigation_server.h.

Private node handle.

Definition at line 292 of file abstract_navigation_server.h.

Definition at line 365 of file abstract_navigation_server.h.

true, if recovery behavior for the MoveBase action is enabled.

Definition at line 350 of file abstract_navigation_server.h.

Definition at line 296 of file abstract_navigation_server.h.

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

Definition at line 326 of file abstract_navigation_server.h.

Definition at line 361 of file abstract_navigation_server.h.

geometry_msgs::PoseStamped mbf_abstract_nav::AbstractNavigationServer::robot_pose_ [protected]

current robot pose; moving controller is responsible to update it by calling getRobotPose

Definition at line 338 of file abstract_navigation_server.h.

true, if the dynamic reconfigure has been setup.

Definition at line 323 of file abstract_navigation_server.h.

shared pointer to the common TransformListener

Definition at line 335 of file abstract_navigation_server.h.

timeout after tf returns without a result

Definition at line 332 of file abstract_navigation_server.h.

cmd_vel publisher for all controller execution objects

Definition at line 356 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 Jun 17 2019 20:11:35