#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_callback, FeedbackCallback feedback_callback) | |
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 &feedback) |
void | updateResult (GoalHandleT &gh, const ActionResultConstPtr &result) |
void | updateStatus (GoalHandleT &gh, const actionlib_msgs::GoalStatusArrayConstPtr &status_array) |
Private Member Functions | |
ACTION_DEFINITION (ActionSpec) | |
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. | |
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 216 of file client_helpers.h.
typedef boost::function<void (const ClientGoalHandle<ActionSpec>&, const FeedbackConstPtr&) > actionlib::CommStateMachine< ActionSpec >::FeedbackCallback |
Definition at line 224 of file client_helpers.h.
typedef ClientGoalHandle<ActionSpec> actionlib::CommStateMachine< ActionSpec >::GoalHandleT |
Definition at line 225 of file client_helpers.h.
typedef boost::function<void (const ClientGoalHandle<ActionSpec>&) > actionlib::CommStateMachine< ActionSpec >::TransitionCallback |
Definition at line 223 of file client_helpers.h.
actionlib::CommStateMachine< ActionSpec >::CommStateMachine | ( | const ActionGoalConstPtr & | action_goal, |
TransitionCallback | transition_callback, | ||
FeedbackCallback | feedback_callback | ||
) |
Definition at line 43 of file comm_state_machine_imp.h.
actionlib::CommStateMachine< ActionSpec >::CommStateMachine | ( | ) | [private] |
actionlib::CommStateMachine< ActionSpec >::ACTION_DEFINITION | ( | ActionSpec | ) | [private] |
const actionlib_msgs::GoalStatus * actionlib::CommStateMachine< ActionSpec >::findGoalStatus | ( | const std::vector< actionlib_msgs::GoalStatus > & | status_vec | ) | const [private] |
Definition at line 99 of file comm_state_machine_imp.h.
CommStateMachine< ActionSpec >::ActionGoalConstPtr actionlib::CommStateMachine< ActionSpec >::getActionGoal | ( | ) | const |
Definition at line 55 of file comm_state_machine_imp.h.
CommState actionlib::CommStateMachine< ActionSpec >::getCommState | ( | ) | const |
Definition at line 61 of file comm_state_machine_imp.h.
actionlib_msgs::GoalStatus actionlib::CommStateMachine< ActionSpec >::getGoalStatus | ( | ) | const |
Definition at line 67 of file comm_state_machine_imp.h.
CommStateMachine< ActionSpec >::ResultConstPtr actionlib::CommStateMachine< ActionSpec >::getResult | ( | ) | const |
Definition at line 73 of file comm_state_machine_imp.h.
void actionlib::CommStateMachine< ActionSpec >::processLost | ( | GoalHandleT & | gh | ) |
Definition at line 440 of file comm_state_machine_imp.h.
void actionlib::CommStateMachine< ActionSpec >::setCommState | ( | const CommState & | state | ) | [private] |
Change the state, as well as print out ROS_DEBUG info.
Definition at line 92 of file comm_state_machine_imp.h.
void actionlib::CommStateMachine< ActionSpec >::setCommState | ( | const CommState::StateEnum & | state | ) | [private] |
Definition at line 86 of file comm_state_machine_imp.h.
void actionlib::CommStateMachine< ActionSpec >::transitionToState | ( | GoalHandleT & | gh, |
const CommState::StateEnum & | next_state | ||
) |
Definition at line 448 of file comm_state_machine_imp.h.
void actionlib::CommStateMachine< ActionSpec >::transitionToState | ( | GoalHandleT & | gh, |
const CommState & | next_state | ||
) |
Definition at line 454 of file comm_state_machine_imp.h.
void actionlib::CommStateMachine< ActionSpec >::updateFeedback | ( | GoalHandleT & | gh, |
const ActionFeedbackConstPtr & | feedback | ||
) |
Definition at line 108 of file comm_state_machine_imp.h.
void actionlib::CommStateMachine< ActionSpec >::updateResult | ( | GoalHandleT & | gh, |
const ActionResultConstPtr & | result | ||
) |
Definition at line 123 of file comm_state_machine_imp.h.
void actionlib::CommStateMachine< ActionSpec >::updateStatus | ( | GoalHandleT & | gh, |
const actionlib_msgs::GoalStatusArrayConstPtr & | status_array | ||
) |
Definition at line 156 of file comm_state_machine_imp.h.
ActionGoalConstPtr actionlib::CommStateMachine< ActionSpec >::action_goal_ [private] |
Definition at line 250 of file client_helpers.h.
FeedbackCallback actionlib::CommStateMachine< ActionSpec >::feedback_cb_ [private] |
Definition at line 256 of file client_helpers.h.
actionlib_msgs::GoalStatus actionlib::CommStateMachine< ActionSpec >::latest_goal_status_ [private] |
Definition at line 251 of file client_helpers.h.
ActionResultConstPtr actionlib::CommStateMachine< ActionSpec >::latest_result_ [private] |
Definition at line 252 of file client_helpers.h.
CommState actionlib::CommStateMachine< ActionSpec >::state_ [private] |
Definition at line 249 of file client_helpers.h.
TransitionCallback actionlib::CommStateMachine< ActionSpec >::transition_cb_ [private] |
Definition at line 255 of file client_helpers.h.