Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
mbf_costmap_nav::CostmapNavigationServer Class Reference

The CostmapNavigationServer makes Move Base Flex backwards compatible to the old move_base. It combines the execution classes which use the nav_core/BaseLocalPlanner, nav_core/BaseCostmapPlanner and the nav_core/RecoveryBehavior base classes as plugin interfaces. These plugin interface are the same for the old move_base. More...

#include <costmap_navigation_server.h>

Inheritance diagram for mbf_costmap_nav::CostmapNavigationServer:
Inheritance graph
[legend]

Public Types

typedef boost::shared_ptr< costmap_2d::Costmap2DROSCostmapPtr
 
typedef boost::shared_ptr< CostmapNavigationServerPtr
 

Public Member Functions

 CostmapNavigationServer (const TFPtr &tf_listener_ptr)
 Constructor. More...
 
virtual void stop ()
 
virtual ~CostmapNavigationServer ()
 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)
 
bool getRobotPose (geometry_msgs::PoseStamped &robot_pose)
 
virtual void initializeServerComponents ()
 
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 callServiceCheckPointCost (mbf_msgs::CheckPoint::Request &request, mbf_msgs::CheckPoint::Response &response)
 Callback method for the check_point_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 callServiceClearCostmaps (std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
 Callback method for the make_plan service. More...
 
void checkActivateCostmaps ()
 Check whether the costmaps should be activated. More...
 
void checkDeactivateCostmaps ()
 Check whether the costmaps should and could be deactivated. More...
 
void deactivateCostmaps (const ros::TimerEvent &event)
 Timer-triggered deactivation of both costmaps. 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 costmap. 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 costmap. 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 costmaps. 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 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 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 name, const mbf_abstract_core::AbstractRecovery::Ptr plugin_ptr)
 shared pointer to a new RecoveryExecution More...
 
void reconfigure (mbf_costmap_nav::MoveBaseFlexConfig &config, uint32_t level)
 Reconfiguration method called by dynamic reconfigure. More...
 

Private Attributes

boost::mutex check_costmaps_mutex_
 Start/stop costmaps 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_point_cost_srv_
 Service Server for the check_point_cost service. More...
 
ros::ServiceServer check_pose_cost_srv_
 Service Server for the check_pose_cost service. More...
 
ros::ServiceServer clear_costmaps_srv_
 Service Server for the clear_costmap service. More...
 
pluginlib::ClassLoader< mbf_costmap_core::CostmapControllercontroller_plugin_loader_
 
uint16_t costmaps_users_
 keep track of plugins using costmaps More...
 
mbf_costmap_nav::MoveBaseFlexConfig default_config_
 the default parameter configuration save More...
 
DynamicReconfigureServerCostmapNav dsrv_costmap_
 Dynamic reconfigure server for the mbf_costmap2d_specific part. More...
 
CostmapPtr global_costmap_ptr_
 Shared pointer to the common global costmap. More...
 
mbf_costmap_nav::MoveBaseFlexConfig last_config_
 last configuration save More...
 
CostmapPtr local_costmap_ptr_
 Shared pointer to the common local costmap. More...
 
pluginlib::ClassLoader< nav_core::BaseLocalPlannernav_core_controller_plugin_loader_
 
pluginlib::ClassLoader< nav_core::BaseGlobalPlannernav_core_planner_plugin_loader_
 
pluginlib::ClassLoader< nav_core::RecoveryBehaviornav_core_recovery_plugin_loader_
 
pluginlib::ClassLoader< mbf_costmap_core::CostmapPlannerplanner_plugin_loader_
 
pluginlib::ClassLoader< mbf_costmap_core::CostmapRecoveryrecovery_plugin_loader_
 
bool setup_reconfigure_
 true, if the dynamic reconfigure has been setup More...
 
bool shutdown_costmaps_
 Stop updating costmaps when not planning or controlling, if true. More...
 
ros::Duration shutdown_costmaps_delay_
 costmpas delayed shutdown delay More...
 
ros::Timer shutdown_costmaps_timer_
 costmpas delayed shutdown timer 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_
 
bool clearing_rotation_allowed_
 
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_
 
geometry_msgs::PoseStamped goal_pose_
 
ros::Publisher goal_pub_
 
mbf_abstract_nav::MoveBaseFlexConfig last_config_
 
MoveBaseAction move_base_action_
 
double oscillation_distance_
 
ros::Duration oscillation_timeout_
 
PlannerAction planner_action_
 
AbstractPluginManager< mbf_abstract_core::AbstractPlannerplanner_plugin_manager_
 
ros::NodeHandle private_nh_
 
RecoveryAction recovery_action_
 
bool recovery_enabled_
 
AbstractPluginManager< mbf_abstract_core::AbstractRecoveryrecovery_plugin_manager_
 
std::string robot_frame_
 
RobotInformation robot_info_
 
geometry_msgs::PoseStamped robot_pose_
 
bool setup_reconfigure_
 
const TFPtr tf_listener_ptr_
 
ros::Duration tf_timeout_
 
ros::Publisher vel_pub_
 

Detailed Description

The CostmapNavigationServer makes Move Base Flex backwards compatible to the old move_base. It combines the execution classes which use the nav_core/BaseLocalPlanner, nav_core/BaseCostmapPlanner and the nav_core/RecoveryBehavior base classes as plugin interfaces. These plugin interface are the same for the old move_base.

Definition at line 78 of file costmap_navigation_server.h.

Member Typedef Documentation

Definition at line 82 of file costmap_navigation_server.h.

Definition at line 84 of file costmap_navigation_server.h.

Constructor & Destructor Documentation

mbf_costmap_nav::CostmapNavigationServer::CostmapNavigationServer ( const TFPtr tf_listener_ptr)

Constructor.

Parameters
tf_listener_ptrShared pointer to a common TransformListener

Definition at line 58 of file costmap_navigation_server.cpp.

mbf_costmap_nav::CostmapNavigationServer::~CostmapNavigationServer ( )
virtual

Destructor.

Definition at line 333 of file costmap_navigation_server.cpp.

Member Function Documentation

bool mbf_costmap_nav::CostmapNavigationServer::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 589 of file costmap_navigation_server.cpp.

bool mbf_costmap_nav::CostmapNavigationServer::callServiceCheckPointCost ( mbf_msgs::CheckPoint::Request &  request,
mbf_msgs::CheckPoint::Response &  response 
)
private

Callback method for the check_point_cost service.

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

Definition at line 387 of file costmap_navigation_server.cpp.

bool mbf_costmap_nav::CostmapNavigationServer::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 465 of file costmap_navigation_server.cpp.

bool mbf_costmap_nav::CostmapNavigationServer::callServiceClearCostmaps ( 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 732 of file costmap_navigation_server.cpp.

void mbf_costmap_nav::CostmapNavigationServer::checkActivateCostmaps ( )
private

Check whether the costmaps should be activated.

Definition at line 746 of file costmap_navigation_server.cpp.

void mbf_costmap_nav::CostmapNavigationServer::checkDeactivateCostmaps ( )
private

Check whether the costmaps should and could be deactivated.

Definition at line 763 of file costmap_navigation_server.cpp.

void mbf_costmap_nav::CostmapNavigationServer::deactivateCostmaps ( const ros::TimerEvent event)
private

Timer-triggered deactivation of both costmaps.

Definition at line 776 of file costmap_navigation_server.cpp.

bool mbf_costmap_nav::CostmapNavigationServer::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 costmap.

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 230 of file costmap_navigation_server.cpp.

bool mbf_costmap_nav::CostmapNavigationServer::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 costmap.

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 178 of file costmap_navigation_server.cpp.

bool mbf_costmap_nav::CostmapNavigationServer::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 costmaps.

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 292 of file costmap_navigation_server.cpp.

mbf_abstract_core::AbstractController::Ptr mbf_costmap_nav::CostmapNavigationServer::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 199 of file costmap_navigation_server.cpp.

mbf_abstract_core::AbstractPlanner::Ptr mbf_costmap_nav::CostmapNavigationServer::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 146 of file costmap_navigation_server.cpp.

mbf_abstract_core::AbstractRecovery::Ptr mbf_costmap_nav::CostmapNavigationServer::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 255 of file costmap_navigation_server.cpp.

mbf_abstract_nav::AbstractControllerExecution::Ptr mbf_costmap_nav::CostmapNavigationServer::newControllerExecution ( const std::string  name,
const mbf_abstract_core::AbstractController::Ptr  plugin_ptr 
)
privatevirtual

shared pointer to a new ControllerExecution

Reimplemented from mbf_abstract_nav::AbstractNavigationServer.

Definition at line 115 of file costmap_navigation_server.cpp.

mbf_abstract_nav::AbstractPlannerExecution::Ptr mbf_costmap_nav::CostmapNavigationServer::newPlannerExecution ( const std::string  name,
const mbf_abstract_core::AbstractPlanner::Ptr  plugin_ptr 
)
privatevirtual

shared pointer to a new PlannerExecution

Reimplemented from mbf_abstract_nav::AbstractNavigationServer.

Definition at line 102 of file costmap_navigation_server.cpp.

mbf_abstract_nav::AbstractRecoveryExecution::Ptr mbf_costmap_nav::CostmapNavigationServer::newRecoveryExecution ( const std::string  name,
const mbf_abstract_core::AbstractRecovery::Ptr  plugin_ptr 
)
privatevirtual

shared pointer to a new RecoveryExecution

Reimplemented from mbf_abstract_nav::AbstractNavigationServer.

Definition at line 131 of file costmap_navigation_server.cpp.

void mbf_costmap_nav::CostmapNavigationServer::reconfigure ( mbf_costmap_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 337 of file costmap_navigation_server.cpp.

void mbf_costmap_nav::CostmapNavigationServer::stop ( )
virtual

Reimplemented from mbf_abstract_nav::AbstractNavigationServer.

Definition at line 324 of file costmap_navigation_server.cpp.

Member Data Documentation

boost::mutex mbf_costmap_nav::CostmapNavigationServer::check_costmaps_mutex_
private

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

Definition at line 273 of file costmap_navigation_server.h.

ros::ServiceServer mbf_costmap_nav::CostmapNavigationServer::check_path_cost_srv_
private

Service Server for the check_path_cost service.

Definition at line 261 of file costmap_navigation_server.h.

ros::ServiceServer mbf_costmap_nav::CostmapNavigationServer::check_point_cost_srv_
private

Service Server for the check_point_cost service.

Definition at line 255 of file costmap_navigation_server.h.

ros::ServiceServer mbf_costmap_nav::CostmapNavigationServer::check_pose_cost_srv_
private

Service Server for the check_pose_cost service.

Definition at line 258 of file costmap_navigation_server.h.

ros::ServiceServer mbf_costmap_nav::CostmapNavigationServer::clear_costmaps_srv_
private

Service Server for the clear_costmap service.

Definition at line 264 of file costmap_navigation_server.h.

pluginlib::ClassLoader<mbf_costmap_core::CostmapController> mbf_costmap_nav::CostmapNavigationServer::controller_plugin_loader_
private

Definition at line 231 of file costmap_navigation_server.h.

uint16_t mbf_costmap_nav::CostmapNavigationServer::costmaps_users_
private

keep track of plugins using costmaps

Definition at line 268 of file costmap_navigation_server.h.

mbf_costmap_nav::MoveBaseFlexConfig mbf_costmap_nav::CostmapNavigationServer::default_config_
private

the default parameter configuration save

Definition at line 243 of file costmap_navigation_server.h.

DynamicReconfigureServerCostmapNav mbf_costmap_nav::CostmapNavigationServer::dsrv_costmap_
private

Dynamic reconfigure server for the mbf_costmap2d_specific part.

Definition at line 237 of file costmap_navigation_server.h.

CostmapPtr mbf_costmap_nav::CostmapNavigationServer::global_costmap_ptr_
private

Shared pointer to the common global costmap.

Definition at line 252 of file costmap_navigation_server.h.

mbf_costmap_nav::MoveBaseFlexConfig mbf_costmap_nav::CostmapNavigationServer::last_config_
private

last configuration save

Definition at line 240 of file costmap_navigation_server.h.

CostmapPtr mbf_costmap_nav::CostmapNavigationServer::local_costmap_ptr_
private

Shared pointer to the common local costmap.

Definition at line 249 of file costmap_navigation_server.h.

pluginlib::ClassLoader<nav_core::BaseLocalPlanner> mbf_costmap_nav::CostmapNavigationServer::nav_core_controller_plugin_loader_
private

Definition at line 232 of file costmap_navigation_server.h.

pluginlib::ClassLoader<nav_core::BaseGlobalPlanner> mbf_costmap_nav::CostmapNavigationServer::nav_core_planner_plugin_loader_
private

Definition at line 234 of file costmap_navigation_server.h.

pluginlib::ClassLoader<nav_core::RecoveryBehavior> mbf_costmap_nav::CostmapNavigationServer::nav_core_recovery_plugin_loader_
private

Definition at line 230 of file costmap_navigation_server.h.

pluginlib::ClassLoader<mbf_costmap_core::CostmapPlanner> mbf_costmap_nav::CostmapNavigationServer::planner_plugin_loader_
private

Definition at line 233 of file costmap_navigation_server.h.

pluginlib::ClassLoader<mbf_costmap_core::CostmapRecovery> mbf_costmap_nav::CostmapNavigationServer::recovery_plugin_loader_
private

Definition at line 229 of file costmap_navigation_server.h.

bool mbf_costmap_nav::CostmapNavigationServer::setup_reconfigure_
private

true, if the dynamic reconfigure has been setup

Definition at line 246 of file costmap_navigation_server.h.

bool mbf_costmap_nav::CostmapNavigationServer::shutdown_costmaps_
private

Stop updating costmaps when not planning or controlling, if true.

Definition at line 267 of file costmap_navigation_server.h.

ros::Duration mbf_costmap_nav::CostmapNavigationServer::shutdown_costmaps_delay_
private

costmpas delayed shutdown delay

Definition at line 270 of file costmap_navigation_server.h.

ros::Timer mbf_costmap_nav::CostmapNavigationServer::shutdown_costmaps_timer_
private

costmpas delayed shutdown timer

Definition at line 269 of file costmap_navigation_server.h.


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


mbf_costmap_nav
Author(s): Sebastian Pütz
autogenerated on Tue Jun 18 2019 19:34:40