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>
Public Types | |
typedef boost::shared_ptr< costmap_2d::Costmap2DROS > | CostmapPtr |
typedef boost::shared_ptr< CostmapNavigationServer > | 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 | 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... | |
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.
typedef boost::shared_ptr<costmap_2d::Costmap2DROS> mbf_costmap_nav::CostmapNavigationServer::CostmapPtr |
Definition at line 82 of file costmap_navigation_server.h.
Definition at line 84 of file costmap_navigation_server.h.
mbf_costmap_nav::CostmapNavigationServer::CostmapNavigationServer | ( | const TFPtr & | tf_listener_ptr | ) |
Constructor.
tf_listener_ptr | Shared pointer to a common TransformListener |
Definition at line 58 of file costmap_navigation_server.cpp.
|
virtual |
Destructor.
Definition at line 333 of file costmap_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 589 of file costmap_navigation_server.cpp.
|
private |
Callback method for the check_point_cost service.
request | Request object, see the mbf_msgs/CheckPoint service definition file. |
response | Response object, see the mbf_msgs/CheckPoint service definition file. |
Definition at line 387 of file costmap_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 465 of file costmap_navigation_server.cpp.
|
private |
Callback method for the make_plan service.
request | Empty request object. |
response | Empty response object. |
Definition at line 732 of file costmap_navigation_server.cpp.
|
private |
Check whether the costmaps should be activated.
Definition at line 746 of file costmap_navigation_server.cpp.
|
private |
Check whether the costmaps should and could be deactivated.
Definition at line 763 of file costmap_navigation_server.cpp.
|
private |
Timer-triggered deactivation of both costmaps.
Definition at line 776 of file costmap_navigation_server.cpp.
|
privatevirtual |
Initializes the controller plugin with its name, a pointer to the TransformListener and pointer to the costmap.
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 230 of file costmap_navigation_server.cpp.
|
privatevirtual |
Initializes the controller plugin with its name and pointer to the costmap.
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 178 of file costmap_navigation_server.cpp.
|
privatevirtual |
Initializes a recovery behavior plugin with its name and pointers to the global and local costmaps.
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 292 of file costmap_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 199 of file costmap_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 146 of file costmap_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 255 of file costmap_navigation_server.cpp.
|
privatevirtual |
shared pointer to a new ControllerExecution
Reimplemented from mbf_abstract_nav::AbstractNavigationServer.
Definition at line 115 of file costmap_navigation_server.cpp.
|
privatevirtual |
shared pointer to a new PlannerExecution
Reimplemented from mbf_abstract_nav::AbstractNavigationServer.
Definition at line 102 of file costmap_navigation_server.cpp.
|
privatevirtual |
shared pointer to a new RecoveryExecution
Reimplemented from mbf_abstract_nav::AbstractNavigationServer.
Definition at line 131 of file costmap_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 337 of file costmap_navigation_server.cpp.
|
virtual |
Reimplemented from mbf_abstract_nav::AbstractNavigationServer.
Definition at line 324 of file costmap_navigation_server.cpp.
|
private |
Start/stop costmaps mutex; concurrent calls to start can lead to segfault.
Definition at line 273 of file costmap_navigation_server.h.
|
private |
Service Server for the check_path_cost service.
Definition at line 261 of file costmap_navigation_server.h.
|
private |
Service Server for the check_point_cost service.
Definition at line 255 of file costmap_navigation_server.h.
|
private |
Service Server for the check_pose_cost service.
Definition at line 258 of file costmap_navigation_server.h.
|
private |
Service Server for the clear_costmap service.
Definition at line 264 of file costmap_navigation_server.h.
|
private |
Definition at line 231 of file costmap_navigation_server.h.
|
private |
keep track of plugins using costmaps
Definition at line 268 of file costmap_navigation_server.h.
|
private |
the default parameter configuration save
Definition at line 243 of file costmap_navigation_server.h.
|
private |
Dynamic reconfigure server for the mbf_costmap2d_specific part.
Definition at line 237 of file costmap_navigation_server.h.
|
private |
Shared pointer to the common global costmap.
Definition at line 252 of file costmap_navigation_server.h.
|
private |
last configuration save
Definition at line 240 of file costmap_navigation_server.h.
|
private |
Shared pointer to the common local costmap.
Definition at line 249 of file costmap_navigation_server.h.
|
private |
Definition at line 232 of file costmap_navigation_server.h.
|
private |
Definition at line 234 of file costmap_navigation_server.h.
|
private |
Definition at line 230 of file costmap_navigation_server.h.
|
private |
Definition at line 233 of file costmap_navigation_server.h.
|
private |
Definition at line 229 of file costmap_navigation_server.h.
|
private |
true, if the dynamic reconfigure has been setup
Definition at line 246 of file costmap_navigation_server.h.
|
private |
Stop updating costmaps when not planning or controlling, if true.
Definition at line 267 of file costmap_navigation_server.h.
|
private |
costmpas delayed shutdown delay
Definition at line 270 of file costmap_navigation_server.h.
|
private |
costmpas delayed shutdown timer
Definition at line 269 of file costmap_navigation_server.h.