Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
mbf_mesh_nav::MeshNavigationServer Class Reference

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>

Inheritance diagram for mbf_mesh_nav::MeshNavigationServer:
Inheritance graph
[legend]

Public Types

typedef boost::shared_ptr< mesh_map::MeshMapMeshPtr
 
typedef boost::shared_ptr< MeshNavigationServerPtr
 

Public Member Functions

 MeshNavigationServer (const TFPtr &tf_listener_ptr)
 Constructor. More...
 
virtual void stop ()
 
virtual ~MeshNavigationServer ()
 Destructor. More...
 
- Public Member Functions inherited from mbf_abstract_nav::AbstractNavigationServer
 AbstractNavigationServer (const TFPtr &tf_listener_ptr)
 
virtual void callActionExePath (ActionServerExePath::GoalHandle goal_handle)
 
virtual void callActionGetPath (ActionServerGetPath::GoalHandle goal_handle)
 
virtual void callActionMoveBase (ActionServerMoveBase::GoalHandle goal_handle)
 
virtual void callActionRecovery (ActionServerRecovery::GoalHandle goal_handle)
 
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)
 
virtual void initializeServerComponents ()
 
virtual mbf_abstract_nav::AbstractControllerExecution::Ptr newControllerExecution (const std::string &plugin_name, const mbf_abstract_core::AbstractController::Ptr &plugin_ptr)
 
virtual mbf_abstract_nav::AbstractPlannerExecution::Ptr newPlannerExecution (const std::string &plugin_name, const mbf_abstract_core::AbstractPlanner::Ptr &plugin_ptr)
 
virtual mbf_abstract_nav::AbstractRecoveryExecution::Ptr newRecoveryExecution (const std::string &plugin_name, const mbf_abstract_core::AbstractRecovery::Ptr &plugin_ptr)
 
virtual void startActionServers ()
 
virtual ~AbstractNavigationServer ()
 

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::MeshControllercontroller_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::MeshPlannerplanner_plugin_loader_
 plugin class loader for planner plugins More...
 
pluginlib::ClassLoader< mbf_mesh_core::MeshRecoveryrecovery_plugin_loader_
 plugin class loader for recovery behaviors plugins More...
 
bool setup_reconfigure_
 true, if the dynamic reconfigure has been setup More...
 

Additional Inherited Members

- Protected Member Functions inherited from mbf_abstract_nav::AbstractNavigationServer
virtual void reconfigure (mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level)
 
virtual void startDynamicReconfigureServer ()
 
bool transformPlanToGlobalFrame (std::vector< geometry_msgs::PoseStamped > &plan, std::vector< geometry_msgs::PoseStamped > &global_plan)
 
- Protected Attributes inherited from mbf_abstract_nav::AbstractNavigationServer
ActionServerExePathPtr action_server_exe_path_ptr_
 
ActionServerGetPathPtr action_server_get_path_ptr_
 
ActionServerMoveBasePtr action_server_move_base_ptr_
 
ActionServerRecoveryPtr action_server_recovery_ptr_
 
boost::mutex configuration_mutex_
 
ControllerAction controller_action_
 
AbstractPluginManager< mbf_abstract_core::AbstractControllercontroller_plugin_manager_
 
mbf_abstract_nav::MoveBaseFlexConfig default_config_
 
DynamicReconfigureServer dsrv_
 
std::string global_frame_
 
ros::Publisher goal_pub_
 
mbf_abstract_nav::MoveBaseFlexConfig last_config_
 
MoveBaseAction move_base_action_
 
PlannerAction planner_action_
 
AbstractPluginManager< mbf_abstract_core::AbstractPlannerplanner_plugin_manager_
 
ros::NodeHandle private_nh_
 
RecoveryAction recovery_action_
 
AbstractPluginManager< mbf_abstract_core::AbstractRecoveryrecovery_plugin_manager_
 
std::string robot_frame_
 
mbf_utility::RobotInformation robot_info_
 
bool setup_reconfigure_
 
const TFPtr tf_listener_ptr_
 
ros::Duration tf_timeout_
 
ros::Publisher vel_pub_
 

Detailed Description

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.

Member Typedef Documentation

◆ MeshPtr

Definition at line 76 of file mesh_navigation_server.h.

◆ Ptr

Definition at line 78 of file mesh_navigation_server.h.

Constructor & Destructor Documentation

◆ MeshNavigationServer()

mbf_mesh_nav::MeshNavigationServer::MeshNavigationServer ( const TFPtr tf_listener_ptr)

Constructor.

Parameters
tf_listener_ptrShared pointer to a common TransformListener

Definition at line 47 of file mesh_navigation_server.cpp.

◆ ~MeshNavigationServer()

mbf_mesh_nav::MeshNavigationServer::~MeshNavigationServer ( )
virtual

Destructor.

Definition at line 228 of file mesh_navigation_server.cpp.

Member Function Documentation

◆ callServiceCheckPathCost()

bool mbf_mesh_nav::MeshNavigationServer::callServiceCheckPathCost ( mbf_msgs::CheckPath::Request &  request,
mbf_msgs::CheckPath::Response &  response 
)
private

Callback method for the check_path_cost service.

Parameters
requestRequest object, see the mbf_msgs/CheckPath service definition file.
responseResponse object, see the mbf_msgs/CheckPath service definition file.
Returns
true, if the service completed successfully, false otherwise

Definition at line 274 of file mesh_navigation_server.cpp.

◆ callServiceCheckPoseCost()

bool mbf_mesh_nav::MeshNavigationServer::callServiceCheckPoseCost ( mbf_msgs::CheckPose::Request &  request,
mbf_msgs::CheckPose::Response &  response 
)
private

Callback method for the check_pose_cost service.

Parameters
requestRequest object, see the mbf_msgs/CheckPose service definition file.
responseResponse object, see the mbf_msgs/CheckPose service definition file.
Returns
true, if the service completed successfully, false otherwise

Definition at line 267 of file mesh_navigation_server.cpp.

◆ callServiceClearMesh()

bool mbf_mesh_nav::MeshNavigationServer::callServiceClearMesh ( std_srvs::Empty::Request &  request,
std_srvs::Empty::Response &  response 
)
private

Callback method for the make_plan service.

Parameters
requestEmpty request object.
responseEmpty response object.
Returns
true, if the service completed successfully, false otherwise

Definition at line 281 of file mesh_navigation_server.cpp.

◆ initializeControllerPlugin()

bool mbf_mesh_nav::MeshNavigationServer::initializeControllerPlugin ( const std::string &  name,
const mbf_abstract_core::AbstractController::Ptr controller_ptr 
)
privatevirtual

Initializes the controller plugin with its name, a pointer to the TransformListener and pointer to the mesh.

Parameters
nameThe name of the controller
controller_ptrpointer to the controller object which corresponds to the name param
Returns
true if init succeeded, false otherwise

Implements mbf_abstract_nav::AbstractNavigationServer.

Definition at line 152 of file mesh_navigation_server.cpp.

◆ initializePlannerPlugin()

bool mbf_mesh_nav::MeshNavigationServer::initializePlannerPlugin ( const std::string &  name,
const mbf_abstract_core::AbstractPlanner::Ptr planner_ptr 
)
privatevirtual

Initializes the controller plugin with its name and pointer to the mesh.

Parameters
nameThe name of the planner
planner_ptrpointer to the planner object which corresponds to the name param
Returns
true if init succeeded, false otherwise

Implements mbf_abstract_nav::AbstractNavigationServer.

Definition at line 119 of file mesh_navigation_server.cpp.

◆ initializeRecoveryPlugin()

bool mbf_mesh_nav::MeshNavigationServer::initializeRecoveryPlugin ( const std::string &  name,
const mbf_abstract_core::AbstractRecovery::Ptr behavior_ptr 
)
privatevirtual

Initializes a recovery behavior plugin with its name and pointers to the global and local meshs.

Parameters
nameThe name of the recovery behavior
behavior_ptrpointer to the recovery behavior object which corresponds to the name param
Returns
true if init succeeded, false otherwise

Implements mbf_abstract_nav::AbstractNavigationServer.

Definition at line 197 of file mesh_navigation_server.cpp.

◆ loadControllerPlugin()

mbf_abstract_core::AbstractController::Ptr mbf_mesh_nav::MeshNavigationServer::loadControllerPlugin ( const std::string &  controller_type)
privatevirtual

Loads the plugin associated with the given controller type parameter.

Parameters
controller_typeThe 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.

Implements mbf_abstract_nav::AbstractNavigationServer.

Definition at line 135 of file mesh_navigation_server.cpp.

◆ loadPlannerPlugin()

mbf_abstract_core::AbstractPlanner::Ptr mbf_mesh_nav::MeshNavigationServer::loadPlannerPlugin ( const std::string &  planner_type)
privatevirtual

Loads the plugin associated with the given planner_type parameter.

Parameters
planner_typeThe type of the planner plugin to load.
Returns
true, if the local planner plugin was successfully loaded.

Implements mbf_abstract_nav::AbstractNavigationServer.

Definition at line 100 of file mesh_navigation_server.cpp.

◆ loadRecoveryPlugin()

mbf_abstract_core::AbstractRecovery::Ptr mbf_mesh_nav::MeshNavigationServer::loadRecoveryPlugin ( const std::string &  recovery_type)
privatevirtual

Loads a Recovery plugin associated with given recovery type parameter.

Parameters
recovery_nameThe name of the Recovery plugin
Returns
A shared pointer to a Recovery plugin, if the plugin was loaded successfully, an empty pointer otherwise.

Implements mbf_abstract_nav::AbstractNavigationServer.

Definition at line 176 of file mesh_navigation_server.cpp.

◆ newControllerExecution()

mbf_abstract_nav::AbstractControllerExecution::Ptr mbf_mesh_nav::MeshNavigationServer::newControllerExecution ( const std::string &  plugin_name,
const mbf_abstract_core::AbstractController::Ptr  plugin_ptr 
)
privatevirtual

shared pointer to a new ControllerExecution

Definition at line 84 of file mesh_navigation_server.cpp.

◆ newPlannerExecution()

mbf_abstract_nav::AbstractPlannerExecution::Ptr mbf_mesh_nav::MeshNavigationServer::newPlannerExecution ( const std::string &  plugin_name,
const mbf_abstract_core::AbstractPlanner::Ptr  plugin_ptr 
)
privatevirtual

shared pointer to a new PlannerExecution

Definition at line 77 of file mesh_navigation_server.cpp.

◆ newRecoveryExecution()

mbf_abstract_nav::AbstractRecoveryExecution::Ptr mbf_mesh_nav::MeshNavigationServer::newRecoveryExecution ( const std::string &  plugin_name,
const mbf_abstract_core::AbstractRecovery::Ptr  plugin_ptr 
)
privatevirtual

shared pointer to a new RecoveryExecution

Definition at line 92 of file mesh_navigation_server.cpp.

◆ reconfigure()

void mbf_mesh_nav::MeshNavigationServer::reconfigure ( mbf_mesh_nav::MoveBaseFlexConfig &  config,
uint32_t  level 
)
private

Reconfiguration method called by dynamic reconfigure.

Parameters
configConfiguration parameters. See the MoveBaseFlexConfig definition.
levelbit mask, which parameters are set.

Definition at line 232 of file mesh_navigation_server.cpp.

◆ stop()

void mbf_mesh_nav::MeshNavigationServer::stop ( )
virtual

Reimplemented from mbf_abstract_nav::AbstractNavigationServer.

Definition at line 220 of file mesh_navigation_server.cpp.

Member Data Documentation

◆ check_meshs_mutex_

boost::mutex mbf_mesh_nav::MeshNavigationServer::check_meshs_mutex_
private

Start/stop meshs mutex; concurrent calls to start can lead to segfault.

Definition at line 233 of file mesh_navigation_server.h.

◆ check_path_cost_srv_

ros::ServiceServer mbf_mesh_nav::MeshNavigationServer::check_path_cost_srv_
private

Service Server for the check_path_cost service.

Definition at line 230 of file mesh_navigation_server.h.

◆ check_pose_cost_srv_

ros::ServiceServer mbf_mesh_nav::MeshNavigationServer::check_pose_cost_srv_
private

Service Server for the check_pose_cost service.

Definition at line 227 of file mesh_navigation_server.h.

◆ clear_mesh_srv_

ros::ServiceServer mbf_mesh_nav::MeshNavigationServer::clear_mesh_srv_
private

Service Server to clear the mesh.

Definition at line 224 of file mesh_navigation_server.h.

◆ controller_plugin_loader_

pluginlib::ClassLoader<mbf_mesh_core::MeshController> mbf_mesh_nav::MeshNavigationServer::controller_plugin_loader_
private

plugin class loader for controller plugins

Definition at line 203 of file mesh_navigation_server.h.

◆ default_config_

mbf_mesh_nav::MoveBaseFlexConfig mbf_mesh_nav::MeshNavigationServer::default_config_
private

the default parameter configuration save

Definition at line 215 of file mesh_navigation_server.h.

◆ dsrv_mesh_

DynamicReconfigureServerMeshNav mbf_mesh_nav::MeshNavigationServer::dsrv_mesh_
private

Dynamic reconfigure server for the mbf_mesh2d_specific part.

Definition at line 209 of file mesh_navigation_server.h.

◆ last_config_

mbf_mesh_nav::MoveBaseFlexConfig mbf_mesh_nav::MeshNavigationServer::last_config_
private

last configuration save

Definition at line 212 of file mesh_navigation_server.h.

◆ mesh_ptr_

MeshPtr mbf_mesh_nav::MeshNavigationServer::mesh_ptr_
private

Shared pointer to the common global mesh.

Definition at line 221 of file mesh_navigation_server.h.

◆ planner_plugin_loader_

pluginlib::ClassLoader<mbf_mesh_core::MeshPlanner> mbf_mesh_nav::MeshNavigationServer::planner_plugin_loader_
private

plugin class loader for planner plugins

Definition at line 206 of file mesh_navigation_server.h.

◆ recovery_plugin_loader_

pluginlib::ClassLoader<mbf_mesh_core::MeshRecovery> mbf_mesh_nav::MeshNavigationServer::recovery_plugin_loader_
private

plugin class loader for recovery behaviors plugins

Definition at line 200 of file mesh_navigation_server.h.

◆ setup_reconfigure_

bool mbf_mesh_nav::MeshNavigationServer::setup_reconfigure_
private

true, if the dynamic reconfigure has been setup

Definition at line 218 of file mesh_navigation_server.h.


The documentation for this class was generated from the following files:


mbf_mesh_nav
Author(s): Sebastian Pütz
autogenerated on Thu Jan 25 2024 03:42:57