37 #ifndef ACTIONLIB__CLIENT__SERVICE_CLIENT_IMP_H_ 38 #define ACTIONLIB__CLIENT__SERVICE_CLIENT_IMP_H_ 46 template<
class ActionSpec>
52 template<
class ActionSpec>
55 return ac_->waitForServer(timeout);
58 template<
class ActionSpec>
61 return ac_->isServerConnected();
64 template<
class ActionSpec>
66 void * result, std::string result_md5sum)
69 const Goal * goal_c =
static_cast<const Goal *
>(goal);
70 Result * result_c =
static_cast<Result *
>(result);
75 if (strcmp(mt::md5sum(*goal_c),
76 goal_md5sum.c_str()) || strcmp(mt::md5sum(*result_c), result_md5sum.c_str()))
78 ROS_ERROR_NAMED(
"actionlib",
"Incorrect md5Sums for goal and result types");
82 if (!ac_->isServerConnected()) {
84 "Attempting to make a service call when the server isn't actually connected to the client.");
88 ac_->sendGoalAndWait(*goal_c);
90 (*result_c) = *(ac_->getResult());
98 template<
class Goal,
class Result>
102 return client_->call(&goal, mt::md5sum(goal), &result, mt::md5sum(result));
107 return client_->waitForServer(timeout);
112 return client_->isServerConnected();
116 template<
class ActionSpec>
124 #endif // ACTIONLIB__CLIENT__SERVICE_CLIENT_IMP_H_ bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0))
ServiceClient serviceClient(ros::NodeHandle n, std::string name)
boost::shared_ptr< ServiceClientImp > client_
bool waitForServer(const ros::Duration &timeout)
bool call(const Goal &goal, Result &result)
A Simple client implementation of the ActionInterface which supports only one goal at a time...
#define ROS_ERROR_NAMED(name,...)
bool call(const void *goal, std::string goal_md5sum, void *result, std::string result_md5sum)
ServiceClientImpT(ros::NodeHandle n, std::string name)
ServiceClient(boost::shared_ptr< ServiceClientImp > client)