Go to the documentation of this file.
38 #ifndef MBF_MESH_NAV__MESH_NAVIGATION_SERVER_H
39 #define MBF_MESH_NAV__MESH_NAVIGATION_SERVER_H
47 #include <mbf_mesh_nav/MoveBaseFlexConfig.h>
48 #include <mbf_msgs/CheckPath.h>
49 #include <mbf_msgs/CheckPose.h>
50 #include <std_srvs/Empty.h>
189 bool callServiceClearMesh(std_srvs::Empty::Request& request, std_srvs::Empty::Response& response);
197 void reconfigure(mbf_mesh_nav::MoveBaseFlexConfig& config, uint32_t level);
bool callServiceCheckPathCost(mbf_msgs::CheckPath::Request &request, mbf_msgs::CheckPath::Response &response)
Callback method for the check_path_cost service.
boost::mutex check_meshs_mutex_
Start/stop meshs mutex; concurrent calls to start can lead to segfault.
ros::ServiceServer check_path_cost_srv_
Service Server for the check_path_cost service.
boost::shared_ptr< dynamic_reconfigure::Server< mbf_mesh_nav::MoveBaseFlexConfig > > DynamicReconfigureServerMeshNav
virtual mbf_abstract_core::AbstractPlanner::Ptr loadPlannerPlugin(const std::string &planner_type)
Loads the plugin associated with the given planner_type parameter.
mbf_mesh_nav::MoveBaseFlexConfig default_config_
the default parameter configuration save
virtual mbf_abstract_core::AbstractRecovery::Ptr loadRecoveryPlugin(const std::string &recovery_type)
Loads a Recovery plugin associated with given recovery type parameter.
bool setup_reconfigure_
true, if the dynamic reconfigure has been setup
The MeshNavigationServer makes Move Base Flex backwards compatible to the old move_base....
ros::ServiceServer clear_mesh_srv_
Service Server to clear the mesh.
virtual ~MeshNavigationServer()
Destructor.
bool callServiceCheckPoseCost(mbf_msgs::CheckPose::Request &request, mbf_msgs::CheckPose::Response &response)
Callback method for the check_pose_cost service.
virtual bool initializePlannerPlugin(const std::string &name, const mbf_abstract_core::AbstractPlanner::Ptr &planner_ptr)
Initializes the controller plugin with its name and pointer to the mesh.
virtual bool initializeRecoveryPlugin(const std::string &name, const mbf_abstract_core::AbstractRecovery::Ptr &behavior_ptr)
Initializes a recovery behavior plugin with its name and pointers to the global and local meshs.
MeshNavigationServer(const TFPtr &tf_listener_ptr)
Constructor.
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
bool callServiceClearMesh(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
Callback method for the make_plan service.
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
DynamicReconfigureServerMeshNav dsrv_mesh_
Dynamic reconfigure server for the mbf_mesh2d_specific part.
virtual mbf_abstract_core::AbstractController::Ptr loadControllerPlugin(const std::string &controller_type)
Loads the plugin associated with the given controller type parameter.
boost::shared_ptr< mesh_map::MeshMap > MeshPtr
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
boost::shared_ptr< MeshNavigationServer > Ptr
pluginlib::ClassLoader< mbf_mesh_core::MeshPlanner > planner_plugin_loader_
plugin class loader for planner plugins
MeshPtr mesh_ptr_
Shared pointer to the common global mesh.
ros::ServiceServer check_pose_cost_srv_
Service Server for the check_pose_cost service.
pluginlib::ClassLoader< mbf_mesh_core::MeshController > controller_plugin_loader_
plugin class loader for controller plugins
pluginlib::ClassLoader< mbf_mesh_core::MeshRecovery > recovery_plugin_loader_
plugin class loader for recovery behaviors plugins
mbf_mesh_nav::MoveBaseFlexConfig last_config_
last configuration save
void reconfigure(mbf_mesh_nav::MoveBaseFlexConfig &config, uint32_t level)
Reconfiguration method called by dynamic reconfigure.
virtual bool initializeControllerPlugin(const std::string &name, const mbf_abstract_core::AbstractController::Ptr &controller_ptr)
Initializes the controller plugin with its name, a pointer to the TransformListener and pointer to th...
mbf_mesh_nav
Author(s): Sebastian Pütz
autogenerated on Thu Jan 25 2024 03:42:57