Go to the documentation of this file.
41 #ifndef MBF_COSTMAP_NAV__COSTMAP_CONTROLLER_EXECUTION_H_
42 #define MBF_COSTMAP_NAV__COSTMAP_CONTROLLER_EXECUTION_H_
47 #include "mbf_costmap_nav/MoveBaseFlexConfig.h"
75 const std::string &controller_name,
81 const MoveBaseFlexConfig &config);
126 const geometry_msgs::PoseStamped &robot_pose,
127 const geometry_msgs::TwistStamped &robot_velocity,
128 geometry_msgs::TwistStamped &vel_cmd,
129 std::string &message);
131 mbf_abstract_nav::MoveBaseFlexConfig
toAbstract(
const MoveBaseFlexConfig &config);
The CostmapControllerExecution binds a local costmap to the AbstractControllerExecution and uses the ...
CostmapControllerExecution(const std::string &controller_name, const mbf_costmap_core::CostmapController::Ptr &controller_ptr, const ros::Publisher &vel_pub, const ros::Publisher &goal_pub, const TFPtr &tf_listener_ptr, const CostmapWrapper::Ptr &costmap_ptr, const MoveBaseFlexConfig &config)
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...
mbf_abstract_nav::MoveBaseFlexConfig toAbstract(const MoveBaseFlexConfig &config)
std::string controller_name_
name of the controller plugin assigned by the class loader
void postRun()
Implementation-specific cleanup function, called right after execution. This method overrides abstrac...
virtual ~CostmapControllerExecution()
Destructor.
void preRun()
Implementation-specific setup function, called right before execution. This method overrides abstract...
const CostmapWrapper::Ptr & costmap_ptr_
Shared pointer to thr local costmap.
bool safetyCheck()
Implementation-specific safety check, called during execution to ensure it's safe to drive....
const TFPtr & tf_listener_ptr
bool lock_costmap_
Whether to lock costmap before calling the controller (see issue #4 for details)
mbf_costmap_nav
Author(s): Sebastian Pütz
autogenerated on Wed Mar 2 2022 00:33:55