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 #ifndef ACTIONLIB_CLIENT_SERVICE_CLIENT_IMP_H_
00038 #define ACTIONLIB_CLIENT_SERVICE_CLIENT_IMP_H_
00039 namespace actionlib {
00040 template <class ActionSpec>
00041 ServiceClientImpT<ActionSpec>::ServiceClientImpT(ros::NodeHandle n, std::string name){
00042 ac_.reset(new SimpleActionClientT(n, name, true));
00043 }
00044
00045 template <class ActionSpec>
00046 bool ServiceClientImpT<ActionSpec>::waitForServer(const ros::Duration& timeout){
00047 return ac_->waitForServer(timeout);
00048 }
00049
00050 template <class ActionSpec>
00051 bool ServiceClientImpT<ActionSpec>::isServerConnected(){
00052 return ac_->isServerConnected();
00053 }
00054
00055 template <class ActionSpec>
00056 bool ServiceClientImpT<ActionSpec>::call(const ros::Message* goal, std::string goal_md5sum, ros::Message* result, std::string result_md5sum){
00057
00058 const Goal* goal_c = static_cast<const Goal*>(goal);
00059 Result* result_c = static_cast<Result*>(result);
00060
00061
00062 namespace mt = ros::message_traits;
00063
00064 if(strcmp(mt::md5sum(*goal_c), goal_md5sum.c_str()) || strcmp(mt::md5sum(*result_c), result_md5sum.c_str()))
00065 {
00066 ROS_ERROR("Incorrect md5Sums for goal and result types");
00067 return false;
00068 }
00069
00070 if(!ac_->isServerConnected()){
00071 ROS_ERROR("Attempting to make a service call when the server isn't actually connected to the client.");
00072 return false;
00073 }
00074
00075 ac_->sendGoalAndWait(*goal_c);
00076 if(ac_->getState() == SimpleClientGoalState::SUCCEEDED){
00077 (*result_c) = *(ac_->getResult());
00078 return true;
00079 }
00080
00081 return false;
00082 }
00083
00084
00085 template <class Goal, class Result>
00086 bool ServiceClient::call(const Goal& goal, Result& result){
00087 namespace mt = ros::message_traits;
00088 return client_->call(&goal, mt::md5sum(goal), &result, mt::md5sum(result));
00089 }
00090
00091 bool ServiceClient::waitForServer(const ros::Duration& timeout){
00092 return client_->waitForServer(timeout);
00093 }
00094
00095 bool ServiceClient::isServerConnected(){
00096 return client_->isServerConnected();
00097 }
00098
00099
00100 template <class ActionSpec>
00101 ServiceClient serviceClient(ros::NodeHandle n, std::string name){
00102 boost::shared_ptr<ServiceClientImp> client_ptr(new ServiceClientImpT<ActionSpec>(n, name));
00103 return ServiceClient(client_ptr);
00104 }
00105
00106 };
00107 #endif