41 #ifndef MBF_ABSTRACT_NAV__CONTROLLER_ACTION_H_    42 #define MBF_ABSTRACT_NAV__CONTROLLER_ACTION_H_    48 #include <mbf_msgs/ExePathAction.h>    53     public AbstractAction<mbf_msgs::ExePathAction, AbstractControllerExecution>
    78           uint32_t outcome, 
const std::string &message,
    79           const geometry_msgs::TwistStamped& current_twist);
    88         uint32_t outcome, 
const std::string &message,
    89         mbf_msgs::ExePathResult &result);
   100 #endif //MBF_ABSTRACT_NAV__CONTROLLER_ACTION_H_ 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. 
geometry_msgs::PoseStamped robot_pose_
Current robot pose. 
void run(GoalHandle &goal_handle, AbstractControllerExecution &execution)
The AbstractControllerExecution class loads and binds the controller plugin. It contains a thread run...
geometry_msgs::PoseStamped goal_pose_
Current goal pose. 
void start(GoalHandle &goal_handle, typename AbstractControllerExecution::Ptr execution_ptr)
Start controller action. Override abstract action version to allow updating current plan without stop...
void publishExePathFeedback(GoalHandle &goal_handle, uint32_t outcome, const std::string &message, const geometry_msgs::TwistStamped ¤t_twist)
ControllerAction(const std::string &name, const RobotInformation &robot_info)
boost::mutex goal_mtx_
lock goal handle for updating it while running 
boost::shared_ptr< ControllerAction > Ptr