#include <controller_action.h>

Public Types | |
| typedef boost::shared_ptr < ControllerAction > | Ptr |
Public Member Functions | |
| ControllerAction (const std::string &name, const RobotInformation &robot_info) | |
| void | run (GoalHandle &goal_handle, AbstractControllerExecution &execution) |
| void | start (GoalHandle &goal_handle, typename AbstractControllerExecution::Ptr execution_ptr) |
| Start controller action. Override abstract action version to allow updating current plan without stopping execution. | |
Protected Member Functions | |
| 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 | publishExePathFeedback (GoalHandle &goal_handle, uint32_t outcome, const std::string &message, const geometry_msgs::TwistStamped ¤t_twist) |
Protected Attributes | |
| boost::mutex | goal_mtx_ |
| lock goal handle for updating it while running | |
| geometry_msgs::PoseStamped | goal_pose_ |
| Current goal pose. | |
| geometry_msgs::PoseStamped | robot_pose_ |
| Current robot pose. | |
Definition at line 52 of file controller_action.h.
| typedef boost::shared_ptr<ControllerAction> mbf_abstract_nav::ControllerAction::Ptr |
Reimplemented from mbf_abstract_nav::AbstractAction< mbf_msgs::ExePathAction, AbstractControllerExecution >.
Definition at line 57 of file controller_action.h.
| mbf_abstract_nav::ControllerAction::ControllerAction | ( | const std::string & | name, |
| const RobotInformation & | robot_info | ||
| ) |
Definition at line 46 of file controller_action.cpp.
| 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.
| outcome | ExePath action outcome |
| message | ExePath action message |
| result | The action result to fill |
Definition at line 345 of file controller_action.cpp.
| void mbf_abstract_nav::ControllerAction::publishExePathFeedback | ( | GoalHandle & | goal_handle, |
| uint32_t | outcome, | ||
| const std::string & | message, | ||
| const geometry_msgs::TwistStamped & | current_twist | ||
| ) | [protected] |
Definition at line 326 of file controller_action.cpp.
| void mbf_abstract_nav::ControllerAction::run | ( | GoalHandle & | goal_handle, |
| AbstractControllerExecution & | execution | ||
| ) |
Definition at line 95 of file controller_action.cpp.
| void mbf_abstract_nav::ControllerAction::start | ( | GoalHandle & | goal_handle, |
| typename AbstractControllerExecution::Ptr | execution_ptr | ||
| ) | [virtual] |
Start controller action. Override abstract action version to allow updating current plan without stopping execution.
| goal_handle | Reference to the goal handle received on action execution callback. |
| execution_ptr | Pointer to the execution descriptor. |
Reimplemented from mbf_abstract_nav::AbstractAction< mbf_msgs::ExePathAction, AbstractControllerExecution >.
Definition at line 53 of file controller_action.cpp.
boost::mutex mbf_abstract_nav::ControllerAction::goal_mtx_ [protected] |
lock goal handle for updating it while running
Definition at line 91 of file controller_action.h.
geometry_msgs::PoseStamped mbf_abstract_nav::ControllerAction::goal_pose_ [protected] |
Current goal pose.
Definition at line 93 of file controller_action.h.
geometry_msgs::PoseStamped mbf_abstract_nav::ControllerAction::robot_pose_ [protected] |
Current robot pose.
Definition at line 92 of file controller_action.h.