Go to the documentation of this file.
38 #ifndef MBF_MESH_NAV__MESH_CONTROLLER_EXECUTION_H
39 #define MBF_MESH_NAV__MESH_CONTROLLER_EXECUTION_H
43 #include <mbf_mesh_nav/MoveBaseFlexConfig.h>
77 const MeshPtr& mesh_ptr,
const MoveBaseFlexConfig& config);
97 const geometry_msgs::TwistStamped& robot_velocity,
98 geometry_msgs::TwistStamped& vel_cmd, std::string& message);
101 mbf_abstract_nav::MoveBaseFlexConfig
toAbstract(
const MoveBaseFlexConfig& config);
std::string controller_name_
name of the controller plugin assigned by the class loader
const MeshPtr & mesh_ptr_
mesh for 3d navigation planning
boost::shared_ptr< mesh_map::MeshMap > MeshPtr
The MeshControllerExecution binds a mesh to the AbstractControllerExecution and uses the mbf_mesh_cor...
MeshControllerExecution(const std::string name, const mbf_mesh_core::MeshController::Ptr &controller_ptr, const ros::Publisher &vel_pub, const ros::Publisher &goal_pub, const TFPtr &tf_listener_ptr, const MeshPtr &mesh_ptr, const MoveBaseFlexConfig &config)
Constructor.
const TFPtr & tf_listener_ptr
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 mesh befo...
virtual ~MeshControllerExecution()
Destructor.
mbf_abstract_nav::MoveBaseFlexConfig toAbstract(const MoveBaseFlexConfig &config)
bool lock_mesh_
Whether to lock mesh before calling the controller.
mbf_mesh_nav
Author(s): Sebastian Pütz
autogenerated on Thu Jan 25 2024 03:42:57