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 #ifndef ROSCPP_ADVERTISE_SERVICE_OPTIONS_H
00029 #define ROSCPP_ADVERTISE_SERVICE_OPTIONS_H
00030
00031 #include "ros/forwards.h"
00032 #include "ros/service_callback_helper.h"
00033 #include "ros/service_traits.h"
00034 #include "ros/message_traits.h"
00035 #include "common.h"
00036
00037 namespace ros
00038 {
00039
00043 struct ROSCPP_DECL AdvertiseServiceOptions
00044 {
00045 AdvertiseServiceOptions()
00046 : callback_queue(0)
00047 {
00048 }
00049
00055 template<class MReq, class MRes>
00056 void init(const std::string& _service, const boost::function<bool(MReq&, MRes&)>& _callback)
00057 {
00058 namespace st = service_traits;
00059 namespace mt = message_traits;
00060 if (st::md5sum<MReq>() != st::md5sum<MRes>())
00061 {
00062 ROS_FATAL("the request and response parameters to the server "
00063 "callback function must be autogenerated from the same "
00064 "server definition file (.srv). your advertise_servce "
00065 "call for %s appeared to use request/response types "
00066 "from different .srv files.", service.c_str());
00067 ROS_BREAK();
00068 }
00069
00070 service = _service;
00071 md5sum = st::md5sum<MReq>();
00072 datatype = st::datatype<MReq>();
00073 req_datatype = mt::datatype<MReq>();
00074 res_datatype = mt::datatype<MRes>();
00075 helper = ServiceCallbackHelperPtr(new ServiceCallbackHelperT<ServiceSpec<MReq, MRes> >(_callback));
00076 }
00077
00083 template<class Service>
00084 void init(const std::string& _service, const boost::function<bool(typename Service::Request&, typename Service::Response&)>& _callback)
00085 {
00086 namespace st = service_traits;
00087 namespace mt = message_traits;
00088 typedef typename Service::Request Request;
00089 typedef typename Service::Response Response;
00090 service = _service;
00091 md5sum = st::md5sum<Service>();
00092 datatype = st::datatype<Service>();
00093 req_datatype = mt::datatype<Request>();
00094 res_datatype = mt::datatype<Response>();
00095 helper = ServiceCallbackHelperPtr(new ServiceCallbackHelperT<ServiceSpec<Request, Response> >(_callback));
00096 }
00097
00103 template<class Spec>
00104 void initBySpecType(const std::string& _service, const typename Spec::CallbackType& _callback)
00105 {
00106 namespace st = service_traits;
00107 namespace mt = message_traits;
00108 typedef typename Spec::RequestType Request;
00109 typedef typename Spec::ResponseType Response;
00110 service = _service;
00111 md5sum = st::md5sum<Request>();
00112 datatype = st::datatype<Request>();
00113 req_datatype = mt::datatype<Request>();
00114 res_datatype = mt::datatype<Response>();
00115 helper = ServiceCallbackHelperPtr(new ServiceCallbackHelperT<Spec>(_callback));
00116 }
00117
00118 std::string service;
00119 std::string md5sum;
00120 std::string datatype;
00121 std::string req_datatype;
00122 std::string res_datatype;
00123
00124 ServiceCallbackHelperPtr helper;
00125
00126 CallbackQueueInterface* callback_queue;
00127
00138 VoidConstPtr tracked_object;
00139
00147 template<class Service>
00148 static AdvertiseServiceOptions create(const std::string& service,
00149 const boost::function<bool(typename Service::Request&, typename Service::Response&)>& callback,
00150 const VoidConstPtr& tracked_object,
00151 CallbackQueueInterface* queue)
00152 {
00153 AdvertiseServiceOptions ops;
00154 ops.init<typename Service::Request, typename Service::Response>(service, callback);
00155 ops.tracked_object = tracked_object;
00156 ops.callback_queue = queue;
00157 return ops;
00158 }
00159 };
00160
00161
00162
00163 }
00164
00165 #endif
00166