Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #ifndef ACTIONLIB__CLIENT__SERVICE_CLIENT_H_
00039 #define ACTIONLIB__CLIENT__SERVICE_CLIENT_H_
00040
00041 #include <actionlib/action_definition.h>
00042 #include <actionlib/client/simple_action_client.h>
00043
00044 #include <string>
00045
00046 namespace actionlib
00047 {
00048
00049 class ServiceClientImp
00050 {
00051 public:
00052 ServiceClientImp() {}
00053 virtual bool call(const void * goal, std::string goal_md5sum, void * result,
00054 std::string result_md5sum) = 0;
00055 virtual bool waitForServer(const ros::Duration & timeout) = 0;
00056 virtual bool isServerConnected() = 0;
00057 virtual ~ServiceClientImp() {}
00058 };
00059
00060 class ServiceClient
00061 {
00062 public:
00063 ServiceClient(boost::shared_ptr<ServiceClientImp> client)
00064 : client_(client) {}
00065
00066 template<class Goal, class Result>
00067 bool call(const Goal & goal, Result & result);
00068
00069 bool waitForServer(const ros::Duration & timeout = ros::Duration(0, 0));
00070 bool isServerConnected();
00071
00072 private:
00073 boost::shared_ptr<ServiceClientImp> client_;
00074 };
00075
00076 template<class ActionSpec>
00077 ServiceClient serviceClient(ros::NodeHandle n, std::string name);
00078
00079 template<class ActionSpec>
00080 class ServiceClientImpT : public ServiceClientImp
00081 {
00082 public:
00083 ACTION_DEFINITION(ActionSpec);
00084 typedef ClientGoalHandle<ActionSpec> GoalHandleT;
00085 typedef SimpleActionClient<ActionSpec> SimpleActionClientT;
00086
00087 ServiceClientImpT(ros::NodeHandle n, std::string name);
00088
00089 bool call(const void * goal, std::string goal_md5sum, void * result, std::string result_md5sum);
00090 bool waitForServer(const ros::Duration & timeout);
00091 bool isServerConnected();
00092
00093 private:
00094 boost::scoped_ptr<SimpleActionClientT> ac_;
00095 };
00096 }
00097
00098
00099 #include <actionlib/client/service_client_imp.h>
00100 #endif // ACTIONLIB__CLIENT__SERVICE_CLIENT_H_