#include <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. More...
|
|
void | publishExePathFeedback (GoalHandle &goal_handle, uint32_t outcome, const std::string &message, const geometry_msgs::TwistStamped ¤t_twist) |
|
Definition at line 55 of file controller_action.h.
◆ Ptr
◆ ControllerAction()
◆ fillExePathResult()
void mbf_abstract_nav::ControllerAction::fillExePathResult |
( |
uint32_t |
outcome, |
|
|
const std::string & |
message, |
|
|
mbf_msgs::ExePathResult & |
result |
|
) |
| |
|
protected |
Utility method to fill the ExePath action result in a single line.
- Parameters
-
outcome | ExePath action outcome |
message | ExePath action message |
result | The action result to fill |
Definition at line 363 of file controller_action.cpp.
◆ publishExePathFeedback()
void mbf_abstract_nav::ControllerAction::publishExePathFeedback |
( |
GoalHandle & |
goal_handle, |
|
|
uint32_t |
outcome, |
|
|
const std::string & |
message, |
|
|
const geometry_msgs::TwistStamped & |
current_twist |
|
) |
| |
|
protected |
◆ runImpl()
◆ start()
Start controller action. Override abstract action version to allow updating current plan without stopping execution.
- Parameters
-
goal_handle | Reference to the goal handle received on action execution callback. |
execution_ptr | Pointer to the execution descriptor. |
Definition at line 53 of file controller_action.cpp.
◆ goal_mtx_
boost::mutex mbf_abstract_nav::ControllerAction::goal_mtx_ |
|
protected |
◆ goal_pose_
geometry_msgs::PoseStamped mbf_abstract_nav::ControllerAction::goal_pose_ |
|
protected |
◆ robot_pose_
geometry_msgs::PoseStamped mbf_abstract_nav::ControllerAction::robot_pose_ |
|
protected |
The documentation for this class was generated from the following files: