#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 &next_state) |
void | transitionToState (GoalHandleT &gh, const CommState::StateEnum &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 99 of file client_helpers.h.
typedef boost::function<void (const ClientGoalHandle<ActionSpec> &, const FeedbackConstPtr &)> actionlib::CommStateMachine< ActionSpec >::FeedbackCallback |
Definition at line 262 of file client_helpers.h.
typedef ClientGoalHandle<ActionSpec> actionlib::CommStateMachine< ActionSpec >::GoalHandleT |
Definition at line 263 of file client_helpers.h.
typedef boost::function<void (const ClientGoalHandle<ActionSpec> &)> actionlib::CommStateMachine< ActionSpec >::TransitionCallback |
Definition at line 260 of file client_helpers.h.
actionlib::CommStateMachine< ActionSpec >::CommStateMachine | ( | const ActionGoalConstPtr & | action_goal, |
TransitionCallback | transition_cb, | ||
FeedbackCallback | feedback_cb | ||
) |
Definition at line 81 of file comm_state_machine_imp.h.
|
private |
|
private |
Definition at line 139 of file comm_state_machine_imp.h.
CommStateMachine< ActionSpec >::ActionGoalConstPtr actionlib::CommStateMachine< ActionSpec >::getActionGoal |
Definition at line 95 of file comm_state_machine_imp.h.
CommState actionlib::CommStateMachine< ActionSpec >::getCommState |
Definition at line 101 of file comm_state_machine_imp.h.
actionlib_msgs::GoalStatus actionlib::CommStateMachine< ActionSpec >::getGoalStatus |
Definition at line 107 of file comm_state_machine_imp.h.
CommStateMachine< ActionSpec >::ResultConstPtr actionlib::CommStateMachine< ActionSpec >::getResult |
Definition at line 113 of file comm_state_machine_imp.h.
void actionlib::CommStateMachine< ActionSpec >::processLost | ( | GoalHandleT & | gh | ) |
Definition at line 495 of file comm_state_machine_imp.h.
|
private |
Change the state, as well as print out ROS_DEBUG info.
Definition at line 131 of file comm_state_machine_imp.h.
|
private |
Definition at line 125 of file comm_state_machine_imp.h.
void actionlib::CommStateMachine< ActionSpec >::transitionToState | ( | GoalHandleT & | gh, |
const CommState & | next_state | ||
) |
Definition at line 510 of file comm_state_machine_imp.h.
void actionlib::CommStateMachine< ActionSpec >::transitionToState | ( | GoalHandleT & | gh, |
const CommState::StateEnum & | next_state | ||
) |
Definition at line 503 of file comm_state_machine_imp.h.
void actionlib::CommStateMachine< ActionSpec >::updateFeedback | ( | GoalHandleT & | gh, |
const ActionFeedbackConstPtr & | action_feedback | ||
) |
Definition at line 151 of file comm_state_machine_imp.h.
void actionlib::CommStateMachine< ActionSpec >::updateResult | ( | GoalHandleT & | gh, |
const ActionResultConstPtr & | action_result | ||
) |
Definition at line 167 of file comm_state_machine_imp.h.
void actionlib::CommStateMachine< ActionSpec >::updateStatus | ( | GoalHandleT & | gh, |
const actionlib_msgs::GoalStatusArrayConstPtr & | status_array | ||
) |
Definition at line 201 of file comm_state_machine_imp.h.
|
private |
Definition at line 289 of file client_helpers.h.
|
private |
Definition at line 295 of file client_helpers.h.
|
private |
Definition at line 290 of file client_helpers.h.
|
private |
Definition at line 291 of file client_helpers.h.
|
private |
Definition at line 288 of file client_helpers.h.
|
private |
Definition at line 294 of file client_helpers.h.