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