41 #ifndef MBF_COSTMAP_NAV__COSTMAP_CONTROLLER_EXECUTION_H_ 42 #define MBF_COSTMAP_NAV__COSTMAP_CONTROLLER_EXECUTION_H_ 45 #include <mbf_costmap_nav/MoveBaseFlexConfig.h> 71 const std::string name,
76 CostmapPtr &costmap_ptr,
77 const MoveBaseFlexConfig &config,
78 boost::function<
void()> setup_fn,
79 boost::function<
void()> cleanup_fn);
98 const geometry_msgs::PoseStamped& robot_pose,
99 const geometry_msgs::TwistStamped& robot_velocity,
100 geometry_msgs::TwistStamped& vel_cmd,
101 std::string& message);
105 mbf_abstract_nav::MoveBaseFlexConfig
toAbstract(
const MoveBaseFlexConfig &config);
mbf_abstract_nav::MoveBaseFlexConfig toAbstract(const MoveBaseFlexConfig &config)
The CostmapControllerExecution binds a local costmap to the AbstractControllerExecution and uses the ...
virtual ~CostmapControllerExecution()
Destructor.
boost::shared_ptr< costmap_2d::Costmap2DROS > CostmapPtr
const TFPtr & tf_listener_ptr
CostmapPtr & costmap_ptr_
costmap for 2d navigation planning
std::string controller_name_
name of the controller plugin assigned by the class loader
bool lock_costmap_
Whether to lock costmap before calling the controller (see issue #4 for details)
CostmapControllerExecution(const std::string name, const mbf_costmap_core::CostmapController::Ptr &controller_ptr, const ros::Publisher &vel_pub, const ros::Publisher &goal_pub, const TFPtr &tf_listener_ptr, CostmapPtr &costmap_ptr, const MoveBaseFlexConfig &config, boost::function< void()> setup_fn, boost::function< void()> cleanup_fn)
Constructor.
virtual uint32_t computeVelocityCmd(const geometry_msgs::PoseStamped &robot_pose, const geometry_msgs::TwistStamped &robot_velocity, geometry_msgs::TwistStamped &vel_cmd, std::string &message)
Request plugin for a new velocity command. We override this method so we can lock the local costmap b...