![]() |
NASA Astrobee Robot Software
0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
|
#include <executive_action_client.h>

Public Member Functions | |
| Action | action () |
| void | action (Action const &action) |
| std::string | cmd_id () |
| void | cmd_id (std::string const &cmd_id) |
| void | SetCmdInfo (Action const &action, std::string const &cmd_id) |
Public Member Functions inherited from ff_util::FreeFlyerActionClient< T > | |
| ACTION_DEFINITION (T) | |
| FreeFlyerActionClient () | |
| ~FreeFlyerActionClient () | |
| void | SetFeedbackCallback (FeedbackCallbackType cb_feedback) |
| void | SetResultCallback (ResultCallbackType cb_result) |
| void | SetConnectedCallback (ConnectedCallbackType cb_connected) |
| void | SetActiveCallback (ActiveCallbackType cb_active) |
| void | SetConnectedTimeout (double to_connected) |
| void | SetActiveTimeout (double to_active) |
| void | SetResponseTimeout (double to_response) |
| void | SetDeadlineTimeout (double to_deadline) |
| void | SetPollTime (double to_poll) |
| bool | Create (ros::NodeHandle *nh, std::string const &topic) |
| bool | IsConnected () |
| bool | SendGoal (Goal const &goal) |
| bool | CancelGoal () |
Additional Inherited Members | |
Public Types inherited from ff_util::FreeFlyerActionClient< T > | |
| typedef std::function< void(FeedbackConstPtr const &) > | FeedbackCallbackType |
| typedef std::function< void(FreeFlyerActionState::Enum, ResultConstPtr const &) > | ResultCallbackType |
| typedef std::function< void(void) > | ConnectedCallbackType |
| typedef std::function< void(void) > | ActiveCallbackType |
Protected Member Functions inherited from ff_util::FreeFlyerActionClient< T > | |
| void | StartOptionalTimer (ros::Timer &timer, ros::Duration const &duration) |
| void | StopAllTimers () |
| void | Complete (FreeFlyerActionState::Enum state, ResultConstPtr const &result) |
| void | ConnectPollCallback (ros::TimerEvent const &event) |
| void | ConnectedTimeoutCallback (ros::TimerEvent const &event) |
| void | ActiveTimeoutCallback (ros::TimerEvent const &event) |
| void | DeadlineTimeoutCallback (ros::TimerEvent const &event) |
| void | ResponseTimeoutCallback (ros::TimerEvent const &event) |
| void | ActiveCallback () |
| void | FeedbackCallback (FeedbackConstPtr const &feedback) |
| void | ResultCallback (actionlib::SimpleClientGoalState const &action_state, ResultConstPtr const &result) |
| void | ResultDelayCallback (ros::TimerEvent const &event) |
Protected Attributes inherited from ff_util::FreeFlyerActionClient< T > | |
| State | state_ |
| ros::Duration | to_connected_ |
| ros::Duration | to_active_ |
| ros::Duration | to_response_ |
| ros::Duration | to_deadline_ |
| ros::Duration | to_poll_ |
| ros::Duration | to_response_delay_ |
| std::shared_ptr< actionlib::SimpleActionClient< T > > | sac_ |
| FeedbackCallbackType | cb_feedback_ |
| ResultCallbackType | cb_result_ |
| ConnectedCallbackType | cb_connected_ |
| ActiveCallbackType | cb_active_ |
| ros::Timer | timer_connected_ |
| ros::Timer | timer_active_ |
| ros::Timer | timer_response_ |
| ros::Timer | timer_deadline_ |
| ros::Timer | timer_poll_ |
| ros::Timer | timer_response_delay_ |
| FreeFlyerActionState::Enum | state_response_ |
| ResultConstPtr | result_ |
| Action executive::ExecutiveActionClient< T >::action |
| void executive::ExecutiveActionClient< T >::action | ( | Action const & | action | ) |
| std::string executive::ExecutiveActionClient< T >::cmd_id |
| void executive::ExecutiveActionClient< T >::cmd_id | ( | std::string const & | cmd_id | ) |
| void executive::ExecutiveActionClient< T >::SetCmdInfo | ( | Action const & | action, |
| std::string const & | cmd_id | ||
| ) |