Go to the documentation of this file.
41 #ifndef MBF_ABSTRACT_NAV__ABSTRACT_NAVIGATION_SERVER_H_
42 #define MBF_ABSTRACT_NAV__ABSTRACT_NAVIGATION_SERVER_H_
46 #include <boost/shared_ptr.hpp>
47 #include <boost/thread/recursive_mutex.hpp>
50 #include <dynamic_reconfigure/server.h>
51 #include <geometry_msgs/PoseStamped.h>
65 #include "mbf_abstract_nav/MoveBaseFlexConfig.h"
143 const std::string &plugin_name,
153 const std::string &plugin_name,
163 const std::string &plugin_name,
196 const std::string &name,
208 const std::string &name,
220 const std::string &name,
281 std::vector<geometry_msgs::PoseStamped> &global_plan);
294 virtual void reconfigure(mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level);
virtual void callActionMoveBase(ActionServerMoveBase::GoalHandle goal_handle)
MoveBase action execution method. This method will be called if the action server receives a goal.
MoveBaseAction move_base_action_
mbf_abstract_nav::MoveBaseFlexConfig last_config_
last configuration save
boost::mutex configuration_mutex_
configuration mutex for derived classes and other threads.
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.
RecoveryAction recovery_action_
ActionServerExePathPtr action_server_exe_path_ptr_
shared pointer to the ExePath action server
AbstractPluginManager< mbf_abstract_core::AbstractPlanner > planner_plugin_manager_
virtual void callActionExePath(ActionServerExePath::GoalHandle goal_handle)
ExePath action execution method. This method will be called if the action server receives a goal.
boost::shared_ptr< ActionServerRecovery > ActionServerRecoveryPtr
mbf_utility::RobotInformation robot_info_
current robot state
actionlib::ActionServer< mbf_msgs::ExePathAction > ActionServerExePath
ExePath action server.
actionlib::ActionServer< mbf_msgs::RecoveryAction > ActionServerRecovery
Recovery action server.
AbstractPluginManager< mbf_abstract_core::AbstractRecovery > recovery_plugin_manager_
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 initializeServerComponents()
initializes all server components. Initializing the plugins of the Planner, the Controller,...
ActionServerGetPathPtr action_server_get_path_ptr_
shared pointer to the GetPath action server
The AbstractNavigationServer is the abstract base class for all navigation servers in move_base_flex ...
boost::shared_ptr< ActionServerMoveBase > ActionServerMoveBasePtr
DynamicReconfigureServer dsrv_
dynamic reconfigure server
ros::NodeHandle private_nh_
Private node handle.
virtual void cancelActionGetPath(ActionServerGetPath::GoalHandle goal_handle)
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.
const std::string name_action_exe_path
ExePath action topic name.
virtual void cancelActionExePath(ActionServerExePath::GoalHandle goal_handle)
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,...
ros::Publisher vel_pub_
cmd_vel publisher for all controller execution objects
boost::shared_ptr< dynamic_reconfigure::Server< mbf_abstract_nav::MoveBaseFlexConfig > > DynamicReconfigureServer
const std::string name_action_get_path
GetPath action topic name.
virtual void callActionGetPath(ActionServerGetPath::GoalHandle goal_handle)
GetPath action execution method. This method will be called if the action server receives a goal.
ActionServerMoveBasePtr action_server_move_base_ptr_
shared pointer to the MoveBase action server
const TFPtr tf_listener_ptr_
shared pointer to the common TransformListener
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.
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,...
actionlib::ActionServer< mbf_msgs::GetPathAction > ActionServerGetPath
GetPath action server.
virtual ~AbstractNavigationServer()
Destructor.
std::string robot_frame_
the robot frame, to get the current robot pose in the global_frame_
virtual mbf_abstract_core::AbstractPlanner::Ptr loadPlannerPlugin(const std::string &planner_type)=0
Loads the plugin associated with the given planner_type parameter.
virtual void reconfigure(mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level)
Reconfiguration method called by dynamic reconfigure.
virtual void startActionServers()
starts all action server.
virtual mbf_abstract_core::AbstractController::Ptr loadControllerPlugin(const std::string &controller_type)=0
Loads the plugin associated with the given controller type parameter.
PlannerAction planner_action_
const std::string name_action_recovery
Recovery action topic name.
std::string global_frame_
the global frame, in which the robot is moving
ControllerAction controller_action_
virtual mbf_abstract_core::AbstractRecovery::Ptr loadRecoveryPlugin(const std::string &recovery_type)=0
Loads a Recovery plugin associated with given recovery type parameter.
ActionServerRecoveryPtr action_server_recovery_ptr_
shared pointer to the Recovery action server
boost::shared_ptr< ActionServerGetPath > ActionServerGetPathPtr
bool setup_reconfigure_
true, if the dynamic reconfigure has been setup.
AbstractPluginManager< mbf_abstract_core::AbstractController > controller_plugin_manager_
const std::string name_action_move_base
MoveBase action topic name.
mbf_abstract_nav::MoveBaseFlexConfig default_config_
the default parameter configuration save
virtual void cancelActionRecovery(ActionServerRecovery::GoalHandle goal_handle)
boost::shared_ptr< ActionServerExePath > ActionServerExePathPtr
virtual void startDynamicReconfigureServer()
Start a dynamic reconfigure server. This must be called only if the extending doesn't create its own.
AbstractNavigationServer(const TFPtr &tf_listener_ptr)
Constructor, reads all parameters and initializes all action servers and creates the plugin instances...
ros::Publisher goal_pub_
current_goal publisher for all controller execution objects
actionlib::ActionServer< mbf_msgs::MoveBaseAction > ActionServerMoveBase
MoveBase action server.
ros::Duration tf_timeout_
timeout after tf returns without a result
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,...
virtual void cancelActionMoveBase(ActionServerMoveBase::GoalHandle goal_handle)
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.
mbf_abstract_nav
Author(s): Sebastian Pütz
autogenerated on Wed Mar 2 2022 00:33:47