NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
ff_util::FreeFlyerServiceClient< ServiceSpec > Class Template Reference

#include <ff_service.h>

Public Types

typedef std::function< void(void) > ConnectedCallbackType
 
typedef std::function< void(void) > TimeoutCallbackType
 

Public Member Functions

void SetTimeoutCallback (TimeoutCallbackType cb_timeout)
 
void SetConnectedCallback (ConnectedCallbackType cb_connected)
 
void SetConnectedTimeout (double to_connected)
 
 FreeFlyerServiceClient ()
 
 ~FreeFlyerServiceClient ()
 
bool Create (ros::NodeHandle *nh, std::string const &topic)
 
bool IsConnected ()
 
bool Call (ServiceSpec &service)
 

Protected Types

enum  State { WAITING_FOR_CREATE = 0, WAITING_FOR_CONNECT = 1, WAITING_FOR_CALL = 2 }
 

Protected Member Functions

void StartOptionalTimer (ros::Timer &timer, ros::Duration const &duration)
 
void ConnectPollCallback (ros::TimerEvent const &event)
 
void TimeoutCallback (ros::TimerEvent const &event)
 

Protected Attributes

State state_
 
ros::Duration to_connected_
 
ros::Duration to_poll_
 
TimeoutCallbackType cb_timeout_
 
ConnectedCallbackType cb_connected_
 
ros::ServiceClient service_
 
ros::Timer timer_connected_
 
ros::Timer timer_poll_
 
std::string topic_
 
ros::NodeHandle * nh_
 

Static Protected Attributes

static constexpr double DEFAULT_TIMEOUT_CONNECTED = 10.0
 
static constexpr double DEFAULT_POLL_DURATION = 0.1
 

Member Typedef Documentation

◆ ConnectedCallbackType

template<class ServiceSpec >
typedef std::function< void (void) > ff_util::FreeFlyerServiceClient< ServiceSpec >::ConnectedCallbackType

◆ TimeoutCallbackType

template<class ServiceSpec >
typedef std::function< void (void) > ff_util::FreeFlyerServiceClient< ServiceSpec >::TimeoutCallbackType

Member Enumeration Documentation

◆ State

template<class ServiceSpec >
enum ff_util::FreeFlyerServiceClient::State
protected
Enumerator
WAITING_FOR_CREATE 
WAITING_FOR_CONNECT 
WAITING_FOR_CALL 

Constructor & Destructor Documentation

◆ FreeFlyerServiceClient()

template<class ServiceSpec >
ff_util::FreeFlyerServiceClient< ServiceSpec >::FreeFlyerServiceClient ( )
inline

◆ ~FreeFlyerServiceClient()

template<class ServiceSpec >
ff_util::FreeFlyerServiceClient< ServiceSpec >::~FreeFlyerServiceClient ( )
inline

Member Function Documentation

◆ Call()

template<class ServiceSpec >
bool ff_util::FreeFlyerServiceClient< ServiceSpec >::Call ( ServiceSpec &  service)
inline

◆ ConnectPollCallback()

template<class ServiceSpec >
void ff_util::FreeFlyerServiceClient< ServiceSpec >::ConnectPollCallback ( ros::TimerEvent const &  event)
inlineprotected

◆ Create()

template<class ServiceSpec >
bool ff_util::FreeFlyerServiceClient< ServiceSpec >::Create ( ros::NodeHandle *  nh,
std::string const &  topic 
)
inline

◆ IsConnected()

template<class ServiceSpec >
bool ff_util::FreeFlyerServiceClient< ServiceSpec >::IsConnected ( )
inline

◆ SetConnectedCallback()

template<class ServiceSpec >
void ff_util::FreeFlyerServiceClient< ServiceSpec >::SetConnectedCallback ( ConnectedCallbackType  cb_connected)
inline

◆ SetConnectedTimeout()

template<class ServiceSpec >
void ff_util::FreeFlyerServiceClient< ServiceSpec >::SetConnectedTimeout ( double  to_connected)
inline

◆ SetTimeoutCallback()

template<class ServiceSpec >
void ff_util::FreeFlyerServiceClient< ServiceSpec >::SetTimeoutCallback ( TimeoutCallbackType  cb_timeout)
inline

◆ StartOptionalTimer()

template<class ServiceSpec >
void ff_util::FreeFlyerServiceClient< ServiceSpec >::StartOptionalTimer ( ros::Timer &  timer,
ros::Duration const &  duration 
)
inlineprotected

◆ TimeoutCallback()

template<class ServiceSpec >
void ff_util::FreeFlyerServiceClient< ServiceSpec >::TimeoutCallback ( ros::TimerEvent const &  event)
inlineprotected

Member Data Documentation

◆ cb_connected_

template<class ServiceSpec >
ConnectedCallbackType ff_util::FreeFlyerServiceClient< ServiceSpec >::cb_connected_
protected

◆ cb_timeout_

template<class ServiceSpec >
TimeoutCallbackType ff_util::FreeFlyerServiceClient< ServiceSpec >::cb_timeout_
protected

◆ DEFAULT_POLL_DURATION

template<class ServiceSpec >
constexpr double ff_util::FreeFlyerServiceClient< ServiceSpec >::DEFAULT_POLL_DURATION = 0.1
staticconstexprprotected

◆ DEFAULT_TIMEOUT_CONNECTED

template<class ServiceSpec >
constexpr double ff_util::FreeFlyerServiceClient< ServiceSpec >::DEFAULT_TIMEOUT_CONNECTED = 10.0
staticconstexprprotected

◆ nh_

template<class ServiceSpec >
ros::NodeHandle* ff_util::FreeFlyerServiceClient< ServiceSpec >::nh_
protected

◆ service_

template<class ServiceSpec >
ros::ServiceClient ff_util::FreeFlyerServiceClient< ServiceSpec >::service_
protected

◆ state_

template<class ServiceSpec >
State ff_util::FreeFlyerServiceClient< ServiceSpec >::state_
protected

◆ timer_connected_

template<class ServiceSpec >
ros::Timer ff_util::FreeFlyerServiceClient< ServiceSpec >::timer_connected_
protected

◆ timer_poll_

template<class ServiceSpec >
ros::Timer ff_util::FreeFlyerServiceClient< ServiceSpec >::timer_poll_
protected

◆ to_connected_

template<class ServiceSpec >
ros::Duration ff_util::FreeFlyerServiceClient< ServiceSpec >::to_connected_
protected

◆ to_poll_

template<class ServiceSpec >
ros::Duration ff_util::FreeFlyerServiceClient< ServiceSpec >::to_poll_
protected

◆ topic_

template<class ServiceSpec >
std::string ff_util::FreeFlyerServiceClient< ServiceSpec >::topic_
protected

The documentation for this class was generated from the following file: