Go to the documentation of this file.
41 #ifndef MBF_COSTMAP_NAV__COSTMAP_NAVIGATION_SERVER_H_
42 #define MBF_COSTMAP_NAV__COSTMAP_NAVIGATION_SERVER_H_
46 #include <std_srvs/Empty.h>
47 #include <mbf_msgs/CheckPath.h>
48 #include <mbf_msgs/CheckPose.h>
49 #include <mbf_msgs/CheckPoint.h>
55 #include "mbf_costmap_nav/MoveBaseFlexConfig.h"
62 #include <boost/unordered_map.hpp>
63 #include <boost/shared_ptr.hpp>
78 typedef boost::unordered_map<std::string, CostmapWrapper::Ptr>
StringToMap;
116 const std::string &plugin_name,
126 const std::string &plugin_name,
136 const std::string &plugin_name,
153 const std::string &name,
173 const std::string &name,
191 const std::string &name,
201 mbf_msgs::CheckPoint::Response &response);
210 mbf_msgs::CheckPose::Response &response);
219 mbf_msgs::CheckPath::Response &response);
234 void reconfigure(mbf_costmap_nav::MoveBaseFlexConfig &config, uint32_t level);
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.
pluginlib::ClassLoader< nav_core::RecoveryBehavior > nav_core_recovery_plugin_loader_
pluginlib::ClassLoader< mbf_costmap_core::CostmapController > controller_plugin_loader_
virtual mbf_abstract_nav::AbstractControllerExecution::Ptr newControllerExecution(const std::string &plugin_name, const mbf_abstract_core::AbstractController::Ptr &plugin_ptr)
Create a new controller execution.
pluginlib::ClassLoader< nav_core::BaseGlobalPlanner > nav_core_planner_plugin_loader_
virtual mbf_abstract_core::AbstractRecovery::Ptr loadRecoveryPlugin(const std::string &recovery_type)
Loads a Recovery plugin associated with given recovery type parameter.
ros::ServiceServer check_point_cost_srv_
Service Server for the check_point_cost service.
mbf_costmap_nav::MoveBaseFlexConfig last_config_
last configuration save
pluginlib::ClassLoader< mbf_costmap_core::CostmapRecovery > recovery_plugin_loader_
DynamicReconfigureServerCostmapNav dsrv_costmap_
Dynamic reconfigure server for the mbf_costmap2d_specific part.
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.
bool callServiceCheckPoseCost(mbf_msgs::CheckPose::Request &request, mbf_msgs::CheckPose::Response &response)
Callback method for the check_pose_cost service.
StringToMap planner_name_to_costmap_ptr_
Maps planner names to the costmap ptr.
The CostmapNavigationServer makes Move Base Flex backwards compatible to the old move_base....
bool setup_reconfigure_
true, if the dynamic reconfigure has been setup
mbf_costmap_nav::MoveBaseFlexConfig default_config_
the default parameter configuration save
virtual ~CostmapNavigationServer()
Destructor.
ros::ServiceServer check_path_cost_srv_
Service Server for the check_path_cost service.
const CostmapWrapper::Ptr local_costmap_ptr_
Shared pointer to the common local costmap.
pluginlib::ClassLoader< mbf_costmap_core::CostmapPlanner > planner_plugin_loader_
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.
ros::ServiceServer check_pose_cost_srv_
Service Server for the check_pose_cost service.
boost::shared_ptr< CostmapNavigationServer > Ptr
CostmapNavigationServer(const TFPtr &tf_listener_ptr)
Constructor.
virtual mbf_abstract_nav::AbstractRecoveryExecution::Ptr newRecoveryExecution(const std::string &plugin_name, const mbf_abstract_core::AbstractRecovery::Ptr &plugin_ptr)
Create a new recovery behavior execution.
bool callServiceCheckPathCost(mbf_msgs::CheckPath::Request &request, mbf_msgs::CheckPath::Response &response)
Callback method for the check_path_cost service.
virtual mbf_abstract_nav::AbstractPlannerExecution::Ptr newPlannerExecution(const std::string &plugin_name, const mbf_abstract_core::AbstractPlanner::Ptr &plugin_ptr)
Create a new planner execution.
boost::shared_ptr< dynamic_reconfigure::Server< mbf_costmap_nav::MoveBaseFlexConfig > > DynamicReconfigureServerCostmapNav
void reconfigure(mbf_costmap_nav::MoveBaseFlexConfig &config, uint32_t level)
Reconfiguration method called by dynamic reconfigure.
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...
virtual mbf_abstract_core::AbstractPlanner::Ptr loadPlannerPlugin(const std::string &planner_type)
Loads the plugin associated with the given planner_type parameter.
bool callServiceCheckPointCost(mbf_msgs::CheckPoint::Request &request, mbf_msgs::CheckPoint::Response &response)
Callback method for the check_point_cost service.
boost::unordered_map< std::string, CostmapWrapper::Ptr > StringToMap
A mapping from a string to a map-ptr.
const CostmapWrapper::Ptr global_costmap_ptr_
Shared pointer to the common global costmap.
StringToMap controller_name_to_costmap_ptr_
Maps the controller names to the costmap ptr.
ros::ServiceServer clear_costmaps_srv_
Service Server for the clear_costmap service.
bool callServiceClearCostmaps(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
Callback method for the make_plan service.
mbf_costmap_nav
Author(s): Sebastian Pütz
autogenerated on Wed Mar 2 2022 00:33:55