#include <mbf_abstract_nav/abstract_navigation_server.h>
#include <std_srvs/Empty.h>
#include <mbf_msgs/CheckPath.h>
#include <mbf_msgs/CheckPose.h>
#include <mbf_msgs/CheckPoint.h>
#include <nav_core/base_global_planner.h>
#include <nav_core/base_local_planner.h>
#include <nav_core/recovery_behavior.h>
#include "mbf_costmap_nav/MoveBaseFlexConfig.h"
#include "mbf_costmap_nav/costmap_planner_execution.h"
#include "mbf_costmap_nav/costmap_controller_execution.h"
#include "mbf_costmap_nav/costmap_recovery_execution.h"
#include "mbf_costmap_nav/costmap_wrapper.h"
#include <boost/unordered_map.hpp>
#include <boost/shared_ptr.hpp>
#include <string>
Go to the source code of this file.
Classes | |
class | mbf_costmap_nav::CostmapNavigationServer |
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... | |
Namespaces | |
mbf_costmap_nav | |
Typedefs | |
typedef boost::shared_ptr< dynamic_reconfigure::Server< mbf_costmap_nav::MoveBaseFlexConfig > > | mbf_costmap_nav::DynamicReconfigureServerCostmapNav |
typedef boost::unordered_map< std::string, CostmapWrapper::Ptr > | mbf_costmap_nav::StringToMap |
A mapping from a string to a map-ptr. More... | |