Go to the documentation of this file.
38 #ifndef ACTIONLIB__CLIENT__SERVICE_CLIENT_H_
39 #define ACTIONLIB__CLIENT__SERVICE_CLIENT_H_
49 class ServiceClientImp
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>
80 class ServiceClientImpT :
public ServiceClientImp
89 bool call(const
void * goal,
std::
string goal_md5sum,
void * result,
std::
string result_md5sum);
99 #include <actionlib/client/service_client_imp.h>
100 #endif // ACTIONLIB__CLIENT__SERVICE_CLIENT_H_
ServiceClient(boost::shared_ptr< ServiceClientImp > client)
bool waitForServer(const ros::Duration &timeout)
#define ACTION_DEFINITION(ActionSpec)
bool call(const Goal &goal, Result &result)
ServiceClient serviceClient(ros::NodeHandle n, std::string name)
virtual bool isServerConnected()=0
ClientGoalHandle< ActionSpec > GoalHandleT
A Simple client implementation of the ActionInterface which supports only one goal at a time.
virtual bool call(const void *goal, std::string goal_md5sum, void *result, std::string result_md5sum)=0
virtual ~ServiceClientImp()
virtual bool waitForServer(const ros::Duration &timeout)=0
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0))
boost::shared_ptr< ServiceClientImp > client_
Client side handle to monitor goal progress.
SimpleActionClient< ActionSpec > SimpleActionClientT
boost::scoped_ptr< SimpleActionClientT > ac_
bool call(const void *goal, std::string goal_md5sum, void *result, std::string result_md5sum)
actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Fri May 19 2023 02:36:55