service_client.h
Go to the documentation of this file.
00001 /*
00002  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *   http://www.apache.org/licenses/LICENSE-2.0
00009 
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016  
00017 
00018 #ifndef _ROS_SERVICE_CLIENT_H_
00019 #define _ROS_SERVICE_CLIENT_H_
00020 
00021 #include "rosserial_msgs/TopicInfo.h"
00022 
00023 #include "publisher.h"
00024 #include "subscriber.h"
00025 
00026 namespace ros {
00027 
00028   template<typename MReq , typename MRes>
00029   class ServiceClient : public Subscriber_  {
00030     public:
00031       ServiceClient(const char* topic_name) : 
00032         pub(topic_name, &req, rosserial_msgs::TopicInfo::ID_SERVICE_CLIENT + rosserial_msgs::TopicInfo::ID_PUBLISHER)
00033       {
00034         this->topic_ = topic_name;
00035         this->waiting = true;
00036       }
00037 
00038       virtual void call(const MReq & request, MRes & response)
00039       {
00040         if(!pub.nh_->connected()) return;
00041         ret = &response;
00042         waiting = true;
00043         pub.publish(&request);
00044         while(waiting && pub.nh_->connected())
00045           if(pub.nh_->spinOnce() < 0) break;
00046       }
00047 
00048       // these refer to the subscriber
00049       virtual void callback(unsigned char *data){
00050         ret->deserialize(data);
00051         waiting = false;
00052       }
00053       virtual const char * getMsgType(){ return this->resp.getType(); }
00054       virtual const char * getMsgMD5(){ return this->resp.getMD5(); }
00055       virtual int getEndpointType(){ return rosserial_msgs::TopicInfo::ID_SERVICE_CLIENT + rosserial_msgs::TopicInfo::ID_SUBSCRIBER; }
00056 
00057       MReq req;
00058       MRes resp;
00059       MRes * ret;
00060       bool waiting;
00061       Publisher pub;
00062   };
00063 
00064 }
00065 
00066 #endif


cob_hand_bridge
Author(s): Mathias Lüdtke
autogenerated on Thu Jun 6 2019 20:43:57