Class AbstractNavigationServer
Defined in File abstract_navigation_server.h
Inheritance Relationships
Derived Type
public mbf_simple_nav::SimpleNavigationServer
Class Documentation
-
class 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().
Subclassed by mbf_simple_nav::SimpleNavigationServer
Public Functions
-
AbstractNavigationServer(const TFPtr &tf_listener_ptr, const rclcpp::Node::SharedPtr &node)
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_ptr – shared pointer to the common TransformListener buffering transformations
-
virtual ~AbstractNavigationServer()
Destructor.
-
virtual void stop()
-
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.
- Parameters:
plugin_name – Name of the planner to use.
plugin_ptr – Shared pointer to the plugin to use.
- Returns:
Shared pointer to a new PlannerExecution.
-
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.
- Parameters:
plugin_name – Name of the controller to use.
plugin_ptr – Shared pointer to the plugin to use.
- Returns:
Shared pointer to a new ControllerExecution.
-
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.
- Parameters:
plugin_name – Name of the recovery behavior to run.
plugin_ptr – Shared pointer to the plugin to use
- Returns:
Shared pointer to a new RecoveryExecution.
-
virtual mbf_abstract_core::AbstractPlanner::Ptr loadPlannerPlugin(const std::string &planner_type) = 0
Loads the plugin associated with the given planner_type parameter.
- Parameters:
planner_type – The type of the planner plugin to load.
- Returns:
Pointer to the loaded plugin
-
virtual mbf_abstract_core::AbstractController::Ptr loadControllerPlugin(const std::string &controller_type) = 0
Loads the plugin associated with the given controller type parameter.
- Parameters:
controller_type – The 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.
-
virtual mbf_abstract_core::AbstractRecovery::Ptr loadRecoveryPlugin(const std::string &recovery_type) = 0
Loads a Recovery plugin associated with given recovery type parameter.
- Parameters:
recovery_name – The name of the Recovery plugin
- Returns:
A shared pointer to a Recovery plugin, if the plugin was loaded successfully, an empty pointer otherwise.
-
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!
- Parameters:
name – The name of the planner
planner_ptr – pointer to the planner object which corresponds to the name param
- Returns:
true if init succeeded, false otherwise
-
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!
- Parameters:
name – The name of the controller
controller_ptr – pointer to the controller object which corresponds to the name param
- Returns:
true if init succeeded, false otherwise
-
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!
- Parameters:
name – The name of the recovery behavior
behavior_ptr – pointer to the recovery behavior object which corresponds to the name param
- Returns:
true if init succeeded, false otherwise
-
virtual rclcpp_action::GoalResponse handleGoalGetPath(const rclcpp_action::GoalUUID &uuid, mbf_msgs::action::GetPath::Goal::ConstSharedPtr goal)
-
virtual void callActionGetPath(ServerGoalHandleGetPathPtr goal_handle)
GetPath action execution method. This method will be called if the action server receives a goal.
- Parameters:
goal – SimpleActionServer goal containing all necessary parameters for the action execution. See the action definitions in mbf_msgs.
-
virtual rclcpp_action::CancelResponse cancelActionGetPath(ServerGoalHandleGetPathPtr goal_handle)
-
virtual rclcpp_action::GoalResponse handleGoalExePath(const rclcpp_action::GoalUUID &uuid, mbf_msgs::action::ExePath::Goal::ConstSharedPtr goal)
-
virtual void callActionExePath(ServerGoalHandleExePathPtr goal_handle)
ExePath action execution method. This method will be called if the action server receives a goal.
- Parameters:
goal – SimpleActionServer goal containing all necessary parameters for the action execution. See the action definitions in mbf_msgs.
-
virtual rclcpp_action::CancelResponse cancelActionExePath(ServerGoalHandleExePathPtr goal_handle)
-
virtual rclcpp_action::GoalResponse handleGoalRecovery(const rclcpp_action::GoalUUID &uuid, mbf_msgs::action::Recovery::Goal::ConstSharedPtr goal)
-
virtual void callActionRecovery(ServerGoalHandleRecoveryPtr goal_handle)
Recovery action execution method. This method will be called if the action server receives a goal.
- Parameters:
goal – SimpleActionServer goal containing all necessary parameters for the action execution. See the action definitions in mbf_msgs.
-
virtual rclcpp_action::CancelResponse cancelActionRecovery(ServerGoalHandleRecoveryPtr goal_handle)
-
virtual rclcpp_action::GoalResponse handleGoalMoveBase(const rclcpp_action::GoalUUID &uuid, mbf_msgs::action::MoveBase::Goal::ConstSharedPtr goal)
-
virtual void callActionMoveBase(ServerGoalHandleMoveBasePtr goal_handle)
MoveBase action execution method. This method will be called if the action server receives a goal.
- Parameters:
goal – SimpleActionServer goal containing all necessary parameters for the action execution. See the action definitions in mbf_msgs.
-
virtual rclcpp_action::CancelResponse cancelActionMoveBase(ServerGoalHandleMoveBasePtr goal_handle)
-
virtual void initializeServerComponents()
initializes all server components. Initializing the plugins of the Planner, the Controller, and the Recovery Behavior.
Protected Functions
-
bool transformPlanToGlobalFrame(std::vector<geometry_msgs::msg::PoseStamped> &plan, std::vector<geometry_msgs::msg::PoseStamped> &global_plan)
Transforms a plan to the global frame (global_frame_) coord system.
- Parameters:
plan – Input plan to be transformed.
global_plan – Output plan, which is then transformed to the global frame.
- Returns:
true, if the transformation succeeded, false otherwise
Protected Attributes
-
rclcpp::Node::SharedPtr node_
Ptr to node for logging, params and communication with other nodes.
-
AbstractPluginManager<mbf_abstract_core::AbstractPlanner> planner_plugin_manager_
-
AbstractPluginManager<mbf_abstract_core::AbstractController> controller_plugin_manager_
-
AbstractPluginManager<mbf_abstract_core::AbstractRecovery> recovery_plugin_manager_
-
ActionServerRecovery::SharedPtr action_server_recovery_ptr_
shared pointer to the Recovery action server
-
ActionServerExePath::SharedPtr action_server_exe_path_ptr_
shared pointer to the ExePath action server
-
ActionServerGetPath::SharedPtr action_server_get_path_ptr_
shared pointer to the GetPath action server
-
ActionServerMoveBase::SharedPtr action_server_move_base_ptr_
shared pointer to the MoveBase action server
-
PlannerAction::Ptr planner_action_
-
ControllerAction::Ptr controller_action_
-
RecoveryAction::Ptr recovery_action_
-
MoveBaseAction::Ptr move_base_action_
-
std::string robot_frame_
the robot frame, to get the current robot pose in the global_frame_
-
std::string global_frame_
the global frame, in which the robot is moving
-
rclcpp::Publisher<geometry_msgs::msg::TwistStamped>::SharedPtr vel_pub_
cmd_vel publisher for all controller execution objects
-
rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr goal_pub_
current_goal publisher for all controller execution objects
-
mbf_utility::RobotInformation::Ptr robot_info_
current robot state
-
AbstractNavigationServer(const TFPtr &tf_listener_ptr, const rclcpp::Node::SharedPtr &node)