The MeshNavigationServer makes Move Base Flex backwards compatible to the old move_base. It combines the execution classes which use the nav_core/BaseLocalPlanner, nav_core/BaseMeshPlanner and the nav_core/RecoveryBehavior base classes as plugin interfaces. These plugin interface are the same for the old move_base. More...
#include <mesh_navigation_server.h>

Public Types | |
| typedef boost::shared_ptr< mesh_map::MeshMap > | MeshPtr |
| typedef boost::shared_ptr< MeshNavigationServer > | Ptr |
Private Member Functions | |
| bool | callServiceCheckPathCost (mbf_msgs::CheckPath::Request &request, mbf_msgs::CheckPath::Response &response) |
| Callback method for the check_path_cost service. More... | |
| bool | callServiceCheckPoseCost (mbf_msgs::CheckPose::Request &request, mbf_msgs::CheckPose::Response &response) |
| Callback method for the check_pose_cost service. More... | |
| bool | callServiceClearMesh (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response) |
| Callback method for the make_plan service. More... | |
| 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 the mesh. More... | |
| 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. More... | |
| 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. More... | |
| virtual mbf_abstract_core::AbstractController::Ptr | loadControllerPlugin (const std::string &controller_type) |
| Loads the plugin associated with the given controller type parameter. More... | |
| virtual mbf_abstract_core::AbstractPlanner::Ptr | loadPlannerPlugin (const std::string &planner_type) |
| Loads the plugin associated with the given planner_type parameter. More... | |
| virtual mbf_abstract_core::AbstractRecovery::Ptr | loadRecoveryPlugin (const std::string &recovery_type) |
| 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... | |
| void | reconfigure (mbf_mesh_nav::MoveBaseFlexConfig &config, uint32_t level) |
| Reconfiguration method called by dynamic reconfigure. More... | |
Private Attributes | |
| boost::mutex | check_meshs_mutex_ |
| Start/stop meshs mutex; concurrent calls to start can lead to segfault. More... | |
| ros::ServiceServer | check_path_cost_srv_ |
| Service Server for the check_path_cost service. More... | |
| ros::ServiceServer | check_pose_cost_srv_ |
| Service Server for the check_pose_cost service. More... | |
| ros::ServiceServer | clear_mesh_srv_ |
| Service Server to clear the mesh. More... | |
| pluginlib::ClassLoader< mbf_mesh_core::MeshController > | controller_plugin_loader_ |
| plugin class loader for controller plugins More... | |
| mbf_mesh_nav::MoveBaseFlexConfig | default_config_ |
| the default parameter configuration save More... | |
| DynamicReconfigureServerMeshNav | dsrv_mesh_ |
| Dynamic reconfigure server for the mbf_mesh2d_specific part. More... | |
| mbf_mesh_nav::MoveBaseFlexConfig | last_config_ |
| last configuration save More... | |
| MeshPtr | mesh_ptr_ |
| Shared pointer to the common global mesh. More... | |
| pluginlib::ClassLoader< mbf_mesh_core::MeshPlanner > | planner_plugin_loader_ |
| plugin class loader for planner plugins More... | |
| pluginlib::ClassLoader< mbf_mesh_core::MeshRecovery > | recovery_plugin_loader_ |
| plugin class loader for recovery behaviors plugins More... | |
| bool | setup_reconfigure_ |
| true, if the dynamic reconfigure has been setup More... | |
The MeshNavigationServer makes Move Base Flex backwards compatible to the old move_base. It combines the execution classes which use the nav_core/BaseLocalPlanner, nav_core/BaseMeshPlanner and the nav_core/RecoveryBehavior base classes as plugin interfaces. These plugin interface are the same for the old move_base.
Definition at line 73 of file mesh_navigation_server.h.
Definition at line 76 of file mesh_navigation_server.h.
Definition at line 78 of file mesh_navigation_server.h.
| mbf_mesh_nav::MeshNavigationServer::MeshNavigationServer | ( | const TFPtr & | tf_listener_ptr | ) |
Constructor.
| tf_listener_ptr | Shared pointer to a common TransformListener |
Definition at line 47 of file mesh_navigation_server.cpp.
|
virtual |
Destructor.
Definition at line 228 of file mesh_navigation_server.cpp.
|
private |
Callback method for the check_path_cost service.
| request | Request object, see the mbf_msgs/CheckPath service definition file. |
| response | Response object, see the mbf_msgs/CheckPath service definition file. |
Definition at line 274 of file mesh_navigation_server.cpp.
|
private |
Callback method for the check_pose_cost service.
| request | Request object, see the mbf_msgs/CheckPose service definition file. |
| response | Response object, see the mbf_msgs/CheckPose service definition file. |
Definition at line 267 of file mesh_navigation_server.cpp.
|
private |
Callback method for the make_plan service.
| request | Empty request object. |
| response | Empty response object. |
Definition at line 281 of file mesh_navigation_server.cpp.
|
privatevirtual |
Initializes the controller plugin with its name, a pointer to the TransformListener and pointer to the mesh.
| name | The name of the controller |
| controller_ptr | pointer to the controller object which corresponds to the name param |
Implements mbf_abstract_nav::AbstractNavigationServer.
Definition at line 152 of file mesh_navigation_server.cpp.
|
privatevirtual |
Initializes the controller plugin with its name and pointer to the mesh.
| name | The name of the planner |
| planner_ptr | pointer to the planner object which corresponds to the name param |
Implements mbf_abstract_nav::AbstractNavigationServer.
Definition at line 119 of file mesh_navigation_server.cpp.
|
privatevirtual |
Initializes a recovery behavior plugin with its name and pointers to the global and local meshs.
| name | The name of the recovery behavior |
| behavior_ptr | pointer to the recovery behavior object which corresponds to the name param |
Implements mbf_abstract_nav::AbstractNavigationServer.
Definition at line 197 of file mesh_navigation_server.cpp.
|
privatevirtual |
Loads the plugin associated with the given controller type parameter.
| controller_type | The type of the controller plugin |
Implements mbf_abstract_nav::AbstractNavigationServer.
Definition at line 135 of file mesh_navigation_server.cpp.
|
privatevirtual |
Loads the plugin associated with the given planner_type parameter.
| planner_type | The type of the planner plugin to load. |
Implements mbf_abstract_nav::AbstractNavigationServer.
Definition at line 100 of file mesh_navigation_server.cpp.
|
privatevirtual |
Loads a Recovery plugin associated with given recovery type parameter.
| recovery_name | The name of the Recovery plugin |
Implements mbf_abstract_nav::AbstractNavigationServer.
Definition at line 176 of file mesh_navigation_server.cpp.
|
privatevirtual |
shared pointer to a new ControllerExecution
Definition at line 84 of file mesh_navigation_server.cpp.
|
privatevirtual |
shared pointer to a new PlannerExecution
Definition at line 77 of file mesh_navigation_server.cpp.
|
privatevirtual |
shared pointer to a new RecoveryExecution
Definition at line 92 of file mesh_navigation_server.cpp.
|
private |
Reconfiguration method called by dynamic reconfigure.
| config | Configuration parameters. See the MoveBaseFlexConfig definition. |
| level | bit mask, which parameters are set. |
Definition at line 232 of file mesh_navigation_server.cpp.
|
virtual |
Reimplemented from mbf_abstract_nav::AbstractNavigationServer.
Definition at line 220 of file mesh_navigation_server.cpp.
|
private |
Start/stop meshs mutex; concurrent calls to start can lead to segfault.
Definition at line 233 of file mesh_navigation_server.h.
|
private |
Service Server for the check_path_cost service.
Definition at line 230 of file mesh_navigation_server.h.
|
private |
Service Server for the check_pose_cost service.
Definition at line 227 of file mesh_navigation_server.h.
|
private |
Service Server to clear the mesh.
Definition at line 224 of file mesh_navigation_server.h.
|
private |
plugin class loader for controller plugins
Definition at line 203 of file mesh_navigation_server.h.
|
private |
the default parameter configuration save
Definition at line 215 of file mesh_navigation_server.h.
|
private |
Dynamic reconfigure server for the mbf_mesh2d_specific part.
Definition at line 209 of file mesh_navigation_server.h.
|
private |
last configuration save
Definition at line 212 of file mesh_navigation_server.h.
|
private |
Shared pointer to the common global mesh.
Definition at line 221 of file mesh_navigation_server.h.
|
private |
plugin class loader for planner plugins
Definition at line 206 of file mesh_navigation_server.h.
|
private |
plugin class loader for recovery behaviors plugins
Definition at line 200 of file mesh_navigation_server.h.
|
private |
true, if the dynamic reconfigure has been setup
Definition at line 218 of file mesh_navigation_server.h.