41 #ifndef MBF_COSTMAP_NAV__COSTMAP_NAVIGATION_SERVER_H_ 42 #define MBF_COSTMAP_NAV__COSTMAP_NAVIGATION_SERVER_H_ 50 #include <mbf_costmap_nav/MoveBaseFlexConfig.h> 51 #include <std_srvs/Empty.h> 52 #include <mbf_msgs/CheckPath.h> 53 #include <mbf_msgs/CheckPose.h> 54 #include <mbf_msgs/CheckPoint.h> 103 const std::string name,
108 const std::string name,
113 const std::string name,
130 const std::string& name,
150 const std::string& name,
168 const std::string& name,
194 mbf_msgs::CheckPoint::Response &response);
203 mbf_msgs::CheckPose::Response &response);
212 mbf_msgs::CheckPath::Response &response);
227 void reconfigure(mbf_costmap_nav::MoveBaseFlexConfig &config, uint32_t level);
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 th...
bool callServiceCheckPathCost(mbf_msgs::CheckPath::Request &request, mbf_msgs::CheckPath::Response &response)
Callback method for the check_path_cost service.
CostmapPtr global_costmap_ptr_
Shared pointer to the common global costmap.
bool callServiceCheckPointCost(mbf_msgs::CheckPoint::Request &request, mbf_msgs::CheckPoint::Response &response)
Callback method for the check_point_cost service.
boost::mutex check_costmaps_mutex_
Start/stop costmaps mutex; concurrent calls to start can lead to segfault.
bool shutdown_costmaps_
Stop updating costmaps when not planning or controlling, if true.
CostmapNavigationServer(const TFPtr &tf_listener_ptr)
Constructor.
void reconfigure(mbf_costmap_nav::MoveBaseFlexConfig &config, uint32_t level)
Reconfiguration method called by dynamic reconfigure.
mbf_costmap_nav::MoveBaseFlexConfig default_config_
the default parameter configuration save
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
virtual ~CostmapNavigationServer()
Destructor.
virtual mbf_abstract_core::AbstractPlanner::Ptr loadPlannerPlugin(const std::string &planner_type)
Loads the plugin associated with the given planner_type parameter.
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...
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
void checkActivateCostmaps()
Check whether the costmaps should be activated.
pluginlib::ClassLoader< mbf_costmap_core::CostmapController > controller_plugin_loader_
boost::shared_ptr< dynamic_reconfigure::Server< mbf_costmap_nav::MoveBaseFlexConfig > > DynamicReconfigureServerCostmapNav
ros::ServiceServer check_point_cost_srv_
Service Server for the check_point_cost service.
ros::ServiceServer clear_costmaps_srv_
Service Server for the clear_costmap service.
mbf_costmap_nav::MoveBaseFlexConfig last_config_
last configuration save
virtual mbf_abstract_core::AbstractRecovery::Ptr loadRecoveryPlugin(const std::string &recovery_type)
Loads a Recovery plugin associated with given recovery type parameter.
ros::Duration shutdown_costmaps_delay_
costmpas delayed shutdown delay
pluginlib::ClassLoader< mbf_costmap_core::CostmapRecovery > recovery_plugin_loader_
DynamicReconfigureServerCostmapNav dsrv_costmap_
Dynamic reconfigure server for the mbf_costmap2d_specific part.
uint16_t costmaps_users_
keep track of plugins using costmaps
CostmapPtr local_costmap_ptr_
Shared pointer to the common local costmap.
bool callServiceClearCostmaps(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
Callback method for the make_plan service.
void checkDeactivateCostmaps()
Check whether the costmaps should and could be deactivated.
ros::Timer shutdown_costmaps_timer_
costmpas delayed shutdown timer
pluginlib::ClassLoader< nav_core::BaseGlobalPlanner > nav_core_planner_plugin_loader_
ros::ServiceServer check_pose_cost_srv_
Service Server for the check_pose_cost service.
bool setup_reconfigure_
true, if the dynamic reconfigure has been setup
pluginlib::ClassLoader< nav_core::RecoveryBehavior > nav_core_recovery_plugin_loader_
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.
ros::ServiceServer check_path_cost_srv_
Service Server for the check_path_cost service.
boost::shared_ptr< costmap_2d::Costmap2DROS > CostmapPtr
pluginlib::ClassLoader< nav_core::BaseLocalPlanner > nav_core_controller_plugin_loader_
virtual mbf_abstract_core::AbstractController::Ptr loadControllerPlugin(const std::string &controller_type)
Loads the plugin associated with the given controller type parameter.
boost::shared_ptr< CostmapNavigationServer > Ptr
void deactivateCostmaps(const ros::TimerEvent &event)
Timer-triggered deactivation of both costmaps.
bool callServiceCheckPoseCost(mbf_msgs::CheckPose::Request &request, mbf_msgs::CheckPose::Response &response)
Callback method for the check_pose_cost service.
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
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.
pluginlib::ClassLoader< mbf_costmap_core::CostmapPlanner > planner_plugin_loader_