38 #ifndef ACTIONLIB__CLIENT__SERVICE_CLIENT_H_ 39 #define ACTIONLIB__CLIENT__SERVICE_CLIENT_H_ 53 virtual bool call(
const void * goal, std::string goal_md5sum,
void * result,
54 std::string result_md5sum) = 0;
66 template<
class Goal,
class Result>
67 bool call(
const Goal & goal, Result & result);
76 template<
class ActionSpec>
79 template<
class ActionSpec>
89 bool call(
const void * goal, std::string goal_md5sum,
void * result, std::string result_md5sum);
94 boost::scoped_ptr<SimpleActionClientT>
ac_;
100 #endif // ACTIONLIB__CLIENT__SERVICE_CLIENT_H_
ClientGoalHandle< ActionSpec > GoalHandleT
ServiceClient serviceClient(ros::NodeHandle n, std::string name)
boost::shared_ptr< ServiceClientImp > client_
virtual bool isServerConnected()=0
virtual ~ServiceClientImp()
virtual bool call(const void *goal, std::string goal_md5sum, void *result, std::string result_md5sum)=0
A Simple client implementation of the ActionInterface which supports only one goal at a time...
virtual bool waitForServer(const ros::Duration &timeout)=0
#define ACTION_DEFINITION(ActionSpec)
SimpleActionClient< ActionSpec > SimpleActionClientT
boost::scoped_ptr< SimpleActionClientT > ac_
Client side handle to monitor goal progress.
ServiceClient(boost::shared_ptr< ServiceClientImp > client)