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) |
bool | getRobotPose (geometry_msgs::PoseStamped &robot_pose) |
Computes the current robot pose (robot_frame_) in the global frame (global_frame_). More... | |
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) |
shared pointer to a new ControllerExecution More... | |
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 More... | |
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 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... | |
bool | clearing_rotation_allowed_ |
true, if clearing rotate is allowed. More... | |
boost::mutex | configuration_mutex_ |
configuration mutex for derived classes and other threads. More... | |
ControllerAction | controller_action_ |
AbstractPluginManager< mbf_abstract_core::AbstractController > | controller_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... | |
geometry_msgs::PoseStamped | goal_pose_ |
current goal pose; used to compute remaining distance and angle 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_ |
double | oscillation_distance_ |
minimal move distance to not detect an oscillation More... | |
ros::Duration | oscillation_timeout_ |
timeout after a oscillation is detected More... | |
PlannerAction | planner_action_ |
AbstractPluginManager< mbf_abstract_core::AbstractPlanner > | planner_plugin_manager_ |
ros::NodeHandle | private_nh_ |
Private node handle. More... | |
RecoveryAction | recovery_action_ |
bool | recovery_enabled_ |
true, if recovery behavior for the MoveBase action is enabled. More... | |
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_ More... | |
RobotInformation | robot_info_ |
geometry_msgs::PoseStamped | robot_pose_ |
current robot pose; moving controller is responsible to update it by calling getRobotPose 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... | |
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.
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.
tf_listener_ptr | shared pointer to the common TransformListener buffering transformations |
planning_ptr | shared pointer to an object of the concrete derived implementation of the AbstractPlannerExecution |
moving_ptr | shared pointer to an object of the concrete derived implementation of the AbstractControllerExecution |
recovery_ptr | shared pointer to an object of the concrete derived implementation of the AbstractRecoveryExecution |
Definition at line 48 of file abstract_navigation_server.cpp.
|
virtual |
Destructor.
Definition at line 125 of file abstract_navigation_server.cpp.
|
virtual |
ExePath action execution method. This method will be called if the action server receives a goal.
goal | SimpleActionServer 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.
|
virtual |
GetPath action execution method. This method will be called if the action server receives a goal.
goal | SimpleActionServer 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.
|
virtual |
MoveBase action execution method. This method will be called if the action server receives a goal.
goal | SimpleActionServer 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.
|
virtual |
Recovery action execution method. This method will be called if the action server receives a goal.
goal | SimpleActionServer 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.
|
virtual |
Definition at line 241 of file abstract_navigation_server.cpp.
|
virtual |
Definition at line 183 of file abstract_navigation_server.cpp.
|
virtual |
Definition at line 311 of file abstract_navigation_server.cpp.
|
virtual |
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_).
robot_pose | Reference to the robot_pose message object to be filled. |
|
pure virtual |
Pure virtual method, the derived class has to implement. Depending on the plugin base class, some plugins need to be initialized!
name | The name of the controller |
controller_ptr | pointer to the controller object which corresponds to the name param |
|
pure virtual |
Pure virtual method, the derived class has to implement. Depending on the plugin base class, some plugins need to be initialized!
name | The name of the planner |
planner_ptr | pointer to the planner object which corresponds to the name param |
|
pure virtual |
Pure virtual method, the derived class has to implement. Depending on the plugin base class, some plugins need to be initialized!
name | The name of the recovery behavior |
behavior_ptr | pointer to the recovery behavior object which corresponds to the name param |
|
virtual |
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.
|
pure virtual |
Loads the plugin associated with the given controller type parameter.
controller_type | The type of the controller plugin |
|
pure virtual |
Loads the plugin associated with the given planner_type parameter.
planner_type | The type of the planner plugin to load. |
|
pure virtual |
Loads a Recovery plugin associated with given recovery type parameter.
recovery_name | The name of the Recovery plugin |
|
virtual |
shared pointer to a new ControllerExecution
Definition at line 326 of file abstract_navigation_server.cpp.
|
virtual |
shared pointer to a new PlannerExecution
Definition at line 317 of file abstract_navigation_server.cpp.
|
virtual |
shared pointer to a new RecoveryExecution
Definition at line 334 of file abstract_navigation_server.cpp.
|
protectedvirtual |
Reconfiguration method called by dynamic reconfigure.
config | Configuration parameters. See the MoveBaseFlexConfig definition. |
level | bit mask, which parameters are set. |
Definition at line 358 of file abstract_navigation_server.cpp.
|
virtual |
starts all action server.
Definition at line 343 of file abstract_navigation_server.cpp.
|
protectedvirtual |
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.
|
virtual |
Definition at line 384 of file abstract_navigation_server.cpp.
|
protected |
Transforms a plan to the global frame (global_frame_) coord system.
plan | Input plan to be transformed. |
global_plan | Output plan, which is then transformed to the global frame. |
|
protected |
shared pointer to the ExePath action server
Definition at line 302 of file abstract_navigation_server.h.
|
protected |
shared pointer to the GetPath action server
Definition at line 305 of file abstract_navigation_server.h.
|
protected |
shared pointer to the MoveBase action server
Definition at line 308 of file abstract_navigation_server.h.
|
protected |
shared pointer to the Recovery action server
Definition at line 299 of file abstract_navigation_server.h.
|
protected |
true, if clearing rotate is allowed.
Definition at line 353 of file abstract_navigation_server.h.
|
protected |
configuration mutex for derived classes and other threads.
Definition at line 314 of file abstract_navigation_server.h.
|
protected |
Definition at line 363 of file abstract_navigation_server.h.
|
protected |
Definition at line 295 of file abstract_navigation_server.h.
|
protected |
the default parameter configuration save
Definition at line 320 of file abstract_navigation_server.h.
|
protected |
dynamic reconfigure server
Definition at line 311 of file abstract_navigation_server.h.
|
protected |
the global frame, in which the robot is moving
Definition at line 329 of file abstract_navigation_server.h.
|
protected |
current goal pose; used to compute remaining distance and angle
Definition at line 341 of file abstract_navigation_server.h.
|
protected |
current_goal publisher for all controller execution objects
Definition at line 359 of file abstract_navigation_server.h.
|
protected |
last configuration save
Definition at line 317 of file abstract_navigation_server.h.
|
protected |
Definition at line 366 of file abstract_navigation_server.h.
|
protected |
minimal move distance to not detect an oscillation
Definition at line 347 of file abstract_navigation_server.h.
|
protected |
timeout after a oscillation is detected
Definition at line 344 of file abstract_navigation_server.h.
|
protected |
Definition at line 364 of file abstract_navigation_server.h.
|
protected |
Definition at line 294 of file abstract_navigation_server.h.
|
protected |
Private node handle.
Definition at line 292 of file abstract_navigation_server.h.
|
protected |
Definition at line 365 of file abstract_navigation_server.h.
|
protected |
true, if recovery behavior for the MoveBase action is enabled.
Definition at line 350 of file abstract_navigation_server.h.
|
protected |
Definition at line 296 of file abstract_navigation_server.h.
|
protected |
the robot frame, to get the current robot pose in the global_frame_
Definition at line 326 of file abstract_navigation_server.h.
|
protected |
Definition at line 361 of file abstract_navigation_server.h.
|
protected |
current robot pose; moving controller is responsible to update it by calling getRobotPose
Definition at line 338 of file abstract_navigation_server.h.
|
protected |
true, if the dynamic reconfigure has been setup.
Definition at line 323 of file abstract_navigation_server.h.
|
protected |
shared pointer to the common TransformListener
Definition at line 335 of file abstract_navigation_server.h.
|
protected |
timeout after tf returns without a result
Definition at line 332 of file abstract_navigation_server.h.
|
protected |
cmd_vel publisher for all controller execution objects
Definition at line 356 of file abstract_navigation_server.h.