Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041 #ifndef MBF_COSTMAP_NAV__COSTMAP_NAVIGATION_SERVER_H_
00042 #define MBF_COSTMAP_NAV__COSTMAP_NAVIGATION_SERVER_H_
00043
00044 #include <mbf_abstract_nav/abstract_navigation_server.h>
00045
00046 #include "costmap_planner_execution.h"
00047 #include "costmap_controller_execution.h"
00048 #include "costmap_recovery_execution.h"
00049
00050 #include <mbf_costmap_nav/MoveBaseFlexConfig.h>
00051 #include <std_srvs/Empty.h>
00052 #include <mbf_msgs/CheckPath.h>
00053 #include <mbf_msgs/CheckPose.h>
00054 #include <mbf_msgs/CheckPoint.h>
00055
00056 #include <nav_core/base_global_planner.h>
00057 #include <nav_core/base_local_planner.h>
00058 #include <nav_core/recovery_behavior.h>
00059
00060 namespace mbf_costmap_nav
00061 {
00068 typedef boost::shared_ptr<dynamic_reconfigure::Server<mbf_costmap_nav::MoveBaseFlexConfig> > DynamicReconfigureServerCostmapNav;
00069
00078 class CostmapNavigationServer : public mbf_abstract_nav::AbstractNavigationServer
00079 {
00080 public:
00081
00082 typedef boost::shared_ptr<costmap_2d::Costmap2DROS> CostmapPtr;
00083
00084 typedef boost::shared_ptr<CostmapNavigationServer> Ptr;
00085
00090 CostmapNavigationServer(const TFPtr &tf_listener_ptr);
00091
00095 virtual ~CostmapNavigationServer();
00096
00097 virtual void stop();
00098
00099 private:
00100
00102 virtual mbf_abstract_nav::AbstractPlannerExecution::Ptr newPlannerExecution(
00103 const std::string name,
00104 const mbf_abstract_core::AbstractPlanner::Ptr plugin_ptr);
00105
00107 virtual mbf_abstract_nav::AbstractControllerExecution::Ptr newControllerExecution(
00108 const std::string name,
00109 const mbf_abstract_core::AbstractController::Ptr plugin_ptr);
00110
00112 virtual mbf_abstract_nav::AbstractRecoveryExecution::Ptr newRecoveryExecution(
00113 const std::string name,
00114 const mbf_abstract_core::AbstractRecovery::Ptr plugin_ptr);
00115
00121 virtual mbf_abstract_core::AbstractPlanner::Ptr loadPlannerPlugin(const std::string& planner_type);
00122
00129 virtual bool initializePlannerPlugin(
00130 const std::string& name,
00131 const mbf_abstract_core::AbstractPlanner::Ptr& planner_ptr
00132 );
00133
00140 virtual mbf_abstract_core::AbstractController::Ptr loadControllerPlugin(const std::string& controller_type);
00141
00149 virtual bool initializeControllerPlugin(
00150 const std::string& name,
00151 const mbf_abstract_core::AbstractController::Ptr& controller_ptr
00152 );
00153
00159 virtual mbf_abstract_core::AbstractRecovery::Ptr loadRecoveryPlugin(const std::string& recovery_type);
00160
00167 virtual bool initializeRecoveryPlugin(
00168 const std::string& name,
00169 const mbf_abstract_core::AbstractRecovery::Ptr& behavior_ptr);
00170
00171
00175 void checkActivateCostmaps();
00176
00180 void checkDeactivateCostmaps();
00181
00185 void deactivateCostmaps(const ros::TimerEvent &event);
00186
00193 bool callServiceCheckPointCost(mbf_msgs::CheckPoint::Request &request,
00194 mbf_msgs::CheckPoint::Response &response);
00195
00202 bool callServiceCheckPoseCost(mbf_msgs::CheckPose::Request &request,
00203 mbf_msgs::CheckPose::Response &response);
00204
00211 bool callServiceCheckPathCost(mbf_msgs::CheckPath::Request &request,
00212 mbf_msgs::CheckPath::Response &response);
00213
00220 bool callServiceClearCostmaps(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response);
00221
00227 void reconfigure(mbf_costmap_nav::MoveBaseFlexConfig &config, uint32_t level);
00228
00229 pluginlib::ClassLoader<mbf_costmap_core::CostmapRecovery> recovery_plugin_loader_;
00230 pluginlib::ClassLoader<nav_core::RecoveryBehavior> nav_core_recovery_plugin_loader_;
00231 pluginlib::ClassLoader<mbf_costmap_core::CostmapController> controller_plugin_loader_;
00232 pluginlib::ClassLoader<nav_core::BaseLocalPlanner> nav_core_controller_plugin_loader_;
00233 pluginlib::ClassLoader<mbf_costmap_core::CostmapPlanner> planner_plugin_loader_;
00234 pluginlib::ClassLoader<nav_core::BaseGlobalPlanner> nav_core_planner_plugin_loader_;
00235
00237 DynamicReconfigureServerCostmapNav dsrv_costmap_;
00238
00240 mbf_costmap_nav::MoveBaseFlexConfig last_config_;
00241
00243 mbf_costmap_nav::MoveBaseFlexConfig default_config_;
00244
00246 bool setup_reconfigure_;
00247
00249 CostmapPtr local_costmap_ptr_;
00250
00252 CostmapPtr global_costmap_ptr_;
00253
00255 ros::ServiceServer check_point_cost_srv_;
00256
00258 ros::ServiceServer check_pose_cost_srv_;
00259
00261 ros::ServiceServer check_path_cost_srv_;
00262
00264 ros::ServiceServer clear_costmaps_srv_;
00265
00267 bool shutdown_costmaps_;
00268 uint16_t costmaps_users_;
00269 ros::Timer shutdown_costmaps_timer_;
00270 ros::Duration shutdown_costmaps_delay_;
00271
00273 boost::mutex check_costmaps_mutex_;
00274 };
00275
00276 }
00277
00278 #endif