Go to the documentation of this file.
41 #ifndef MBF_ABSTRACT_NAV__CONTROLLER_ACTION_H_
42 #define MBF_ABSTRACT_NAV__CONTROLLER_ACTION_H_
46 #include <mbf_msgs/ExePathAction.h>
49 #include "mbf_abstract_nav/abstract_action_base.hpp"
56 public AbstractActionBase<mbf_msgs::ExePathAction, AbstractControllerExecution>
72 GoalHandle &goal_handle,
80 GoalHandle &goal_handle,
81 uint32_t outcome,
const std::string &message,
82 const geometry_msgs::TwistStamped ¤t_twist);
91 uint32_t outcome,
const std::string &message,
92 mbf_msgs::ExePathResult &result);
103 #endif //MBF_ABSTRACT_NAV__CONTROLLER_ACTION_H_
boost::mutex goal_mtx_
lock goal handle for updating it while running
geometry_msgs::PoseStamped goal_pose_
Current goal pose.
void fillExePathResult(uint32_t outcome, const std::string &message, mbf_msgs::ExePathResult &result)
Utility method to fill the ExePath action result in a single line.
void runImpl(GoalHandle &goal_handle, AbstractControllerExecution &execution)
void publishExePathFeedback(GoalHandle &goal_handle, uint32_t outcome, const std::string &message, const geometry_msgs::TwistStamped ¤t_twist)
geometry_msgs::PoseStamped robot_pose_
Current robot pose.
boost::shared_ptr< ControllerAction > Ptr
void start(GoalHandle &goal_handle, typename AbstractControllerExecution::Ptr execution_ptr)
Start controller action. Override abstract action version to allow updating current plan without stop...
ControllerAction(const std::string &name, const mbf_utility::RobotInformation &robot_info)
The AbstractControllerExecution class loads and binds the controller plugin. It contains a thread run...
mbf_abstract_nav
Author(s): Sebastian Pütz
autogenerated on Wed Mar 2 2022 00:33:47