#include <client_helpers.h>
Public Types | |
| typedef boost::function< void(const ClientGoalHandle< ActionSpec > &, const FeedbackConstPtr &)> | FeedbackCallback |
| typedef ClientGoalHandle< ActionSpec > | GoalHandleT |
| typedef boost::function< void(const ClientGoalHandle< ActionSpec > &)> | TransitionCallback |
Public Member Functions | |
| CommStateMachine (const ActionGoalConstPtr &action_goal, TransitionCallback transition_cb, FeedbackCallback feedback_cb) | |
| ActionGoalConstPtr | getActionGoal () const |
| CommState | getCommState () const |
| actionlib_msgs::GoalStatus | getGoalStatus () const |
| ResultConstPtr | getResult () const |
| void | processLost (GoalHandleT &gh) |
| void | transitionToState (GoalHandleT &gh, const CommState::StateEnum &next_state) |
| void | transitionToState (GoalHandleT &gh, const CommState &next_state) |
| void | updateFeedback (GoalHandleT &gh, const ActionFeedbackConstPtr &action_feedback) |
| void | updateResult (GoalHandleT &gh, const ActionResultConstPtr &action_result) |
| void | updateStatus (GoalHandleT &gh, const actionlib_msgs::GoalStatusArrayConstPtr &status_array) |
Private Member Functions | |
| CommStateMachine () | |
| const actionlib_msgs::GoalStatus * | findGoalStatus (const std::vector< actionlib_msgs::GoalStatus > &status_vec) const |
| void | setCommState (const CommState &state) |
| Change the state, as well as print out ROS_DEBUG info. More... | |
| void | setCommState (const CommState::StateEnum &state) |
Private Attributes | |
| ActionGoalConstPtr | action_goal_ |
| FeedbackCallback | feedback_cb_ |
| actionlib_msgs::GoalStatus | latest_goal_status_ |
| ActionResultConstPtr | latest_result_ |
| CommState | state_ |
| TransitionCallback | transition_cb_ |
Definition at line 67 of file client_helpers.h.
| typedef boost::function<void (const ClientGoalHandle<ActionSpec> &, const FeedbackConstPtr &)> actionlib::CommStateMachine< ActionSpec >::FeedbackCallback |
Definition at line 230 of file client_helpers.h.
| typedef ClientGoalHandle<ActionSpec> actionlib::CommStateMachine< ActionSpec >::GoalHandleT |
Definition at line 231 of file client_helpers.h.
| typedef boost::function<void (const ClientGoalHandle<ActionSpec> &)> actionlib::CommStateMachine< ActionSpec >::TransitionCallback |
Definition at line 228 of file client_helpers.h.
| actionlib::CommStateMachine< ActionSpec >::CommStateMachine | ( | const ActionGoalConstPtr & | action_goal, |
| TransitionCallback | transition_cb, | ||
| FeedbackCallback | feedback_cb | ||
| ) |
Definition at line 49 of file comm_state_machine_imp.h.
|
private |
|
private |
Definition at line 107 of file comm_state_machine_imp.h.
| CommStateMachine< ActionSpec >::ActionGoalConstPtr actionlib::CommStateMachine< ActionSpec >::getActionGoal | ( | ) | const |
Definition at line 63 of file comm_state_machine_imp.h.
| CommState actionlib::CommStateMachine< ActionSpec >::getCommState | ( | ) | const |
Definition at line 69 of file comm_state_machine_imp.h.
| actionlib_msgs::GoalStatus actionlib::CommStateMachine< ActionSpec >::getGoalStatus | ( | ) | const |
Definition at line 75 of file comm_state_machine_imp.h.
| CommStateMachine< ActionSpec >::ResultConstPtr actionlib::CommStateMachine< ActionSpec >::getResult | ( | ) | const |
Definition at line 81 of file comm_state_machine_imp.h.
| void actionlib::CommStateMachine< ActionSpec >::processLost | ( | GoalHandleT & | gh | ) |
Definition at line 463 of file comm_state_machine_imp.h.
|
private |
Change the state, as well as print out ROS_DEBUG info.
Definition at line 99 of file comm_state_machine_imp.h.
|
private |
Definition at line 93 of file comm_state_machine_imp.h.
| void actionlib::CommStateMachine< ActionSpec >::transitionToState | ( | GoalHandleT & | gh, |
| const CommState::StateEnum & | next_state | ||
| ) |
Definition at line 471 of file comm_state_machine_imp.h.
| void actionlib::CommStateMachine< ActionSpec >::transitionToState | ( | GoalHandleT & | gh, |
| const CommState & | next_state | ||
| ) |
Definition at line 478 of file comm_state_machine_imp.h.
| void actionlib::CommStateMachine< ActionSpec >::updateFeedback | ( | GoalHandleT & | gh, |
| const ActionFeedbackConstPtr & | action_feedback | ||
| ) |
Definition at line 119 of file comm_state_machine_imp.h.
| void actionlib::CommStateMachine< ActionSpec >::updateResult | ( | GoalHandleT & | gh, |
| const ActionResultConstPtr & | action_result | ||
| ) |
Definition at line 135 of file comm_state_machine_imp.h.
| void actionlib::CommStateMachine< ActionSpec >::updateStatus | ( | GoalHandleT & | gh, |
| const actionlib_msgs::GoalStatusArrayConstPtr & | status_array | ||
| ) |
Definition at line 169 of file comm_state_machine_imp.h.
|
private |
Definition at line 257 of file client_helpers.h.
|
private |
Definition at line 263 of file client_helpers.h.
|
private |
Definition at line 258 of file client_helpers.h.
|
private |
Definition at line 259 of file client_helpers.h.
|
private |
Definition at line 256 of file client_helpers.h.
|
private |
Definition at line 262 of file client_helpers.h.