test_intra.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2010, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include <rve_rpc/client.h>
00031 #include <rve_rpc/server.h>
00032 
00033 #include <rve_rpc/TestRequest.h>
00034 #include <rve_rpc/TestResponse.h>
00035 
00036 #include <ros/ros.h>
00037 
00038 #include <gtest/gtest.h>
00039 
00040 #include <boost/thread.hpp>
00041 
00042 using namespace rve_rpc;
00043 
00044 void doubleCallback(CallHandle<TestRequest, TestResponse>& handle)
00045 {
00046   TestResponsePtr res(new TestResponse);
00047   res->value = handle.getRequest()->value * 2;
00048   handle.respond(res);
00049 }
00050 
00051 void tripleCallback(CallHandle<TestRequest, TestResponse>& handle)
00052 {
00053   TestResponsePtr res(new TestResponse);
00054   res->value = handle.getRequest()->value * 3;
00055   handle.respond(res);
00056 }
00057 
00058 TEST(Intra, callWithReturn)
00059 {
00060   ros::AsyncSpinner sp(1);
00061   sp.start();
00062   ros::NodeHandle nh;
00063   Server s("test", nh);
00064   s.addMethod<TestRequest, TestResponse>("double", doubleCallback);
00065   s.ready();
00066 
00067   Client c("test", nh);
00068   Method<TestRequest, TestResponse> m = c.addMethod<TestRequest, TestResponse>("double");
00069   c.connect();
00070 
00071   TestRequestPtr req(new TestRequest);
00072   req->value = 5;
00073   TestResponseConstPtr res = m.call(req);
00074   EXPECT_EQ(res->value, 10U);
00075 }
00076 
00077 TEST(Intra, multipleMethodsWithReturn)
00078 {
00079   ros::AsyncSpinner sp(1);
00080   sp.start();
00081   ros::NodeHandle nh;
00082   Server s("test", nh);
00083   s.addMethod<TestRequest, TestResponse>("double", doubleCallback);
00084   s.addMethod<TestRequest, TestResponse>("triple", tripleCallback);
00085   s.ready();
00086 
00087   Client c("test", nh);
00088   Method<TestRequest, TestResponse> d = c.addMethod<TestRequest, TestResponse>("double");
00089   Method<TestRequest, TestResponse> t = c.addMethod<TestRequest, TestResponse>("triple");
00090   c.connect();
00091 
00092   {
00093     TestRequestPtr req(new TestRequest);
00094     req->value = 5;
00095     TestResponseConstPtr res = d.call(req);
00096     EXPECT_EQ(res->value, 10U);
00097   }
00098 
00099   {
00100     TestRequestPtr req(new TestRequest);
00101     req->value = 20;
00102     TestResponseConstPtr res = t.call(req);
00103     EXPECT_EQ(res->value, 60U);
00104   }
00105 }
00106 
00107 TEST(Intra, callUnknownMethod)
00108 {
00109   ros::AsyncSpinner sp(1);
00110   sp.start();
00111   ros::NodeHandle nh;
00112   Server s("test", nh);
00113   s.addMethod<TestRequest, TestResponse>("double", doubleCallback);
00114   s.ready();
00115 
00116   Client c("test", nh);
00117   Method<TestRequest, TestResponse> m = c.addMethod<TestRequest, TestResponse>("triple");
00118   c.connect();
00119 
00120   TestRequestPtr req(new TestRequest);
00121   req->value = 5;
00122 
00123   try
00124   {
00125     TestResponseConstPtr res = m.call(req);
00126     FAIL();
00127   }
00128   catch (CallException& e)
00129   {
00130     ROS_INFO("%s", e.what());
00131     SUCCEED();
00132   }
00133 }
00134 
00135 TEST(Intra, connectAsync)
00136 {
00137   ros::NodeHandle nh;
00138   Server s("test", nh);
00139   s.addMethod<TestRequest, TestResponse>("double", doubleCallback);
00140   s.ready();
00141 
00142   Client c("test", nh);
00143   Method<TestRequest, TestResponse> m = c.addMethod<TestRequest, TestResponse>("double");
00144   c.connectAsync();
00145   ASSERT_FALSE(c.isConnected());
00146   while (!c.isConnected())
00147   {
00148     ros::spinOnce();
00149     ros::WallDuration(0.01).sleep();
00150   }
00151 
00152   ros::AsyncSpinner sp(1);
00153   sp.start();
00154   TestRequestPtr req(new TestRequest);
00155   req->value = 5;
00156   TestResponseConstPtr res = m.call(req);
00157   EXPECT_EQ(res->value, 10U);
00158 }
00159 
00160 struct NoCopyHelper
00161 {
00162   void cb(CallHandle<TestRequest, TestResponse>& handle)
00163   {
00164     req_ = handle.getRequest();
00165     res_.reset(new TestResponse);
00166     res_->value = req_->value * 2;
00167     handle.respond(res_);
00168   }
00169 
00170   TestRequestConstPtr req_;
00171   TestResponsePtr res_;
00172 };
00173 
00174 TEST(Intra, noCopy)
00175 {
00176   ros::AsyncSpinner sp(1);
00177   sp.start();
00178   ros::NodeHandle nh;
00179   Server s("test", nh);
00180   NoCopyHelper h;
00181   s.addMethod<TestRequest, TestResponse>("double", boost::bind(&NoCopyHelper::cb, &h, _1));
00182   s.ready();
00183 
00184   Client c("test", nh);
00185   Method<TestRequest, TestResponse> m = c.addMethod<TestRequest, TestResponse>("double");
00186   c.connect();
00187 
00188   TestRequestPtr req(new TestRequest);
00189   req->value = 5;
00190   TestResponseConstPtr res = m.call(req);
00191   EXPECT_EQ(res->value, 10U);
00192   EXPECT_EQ(req, h.req_);
00193   EXPECT_EQ(res, h.res_);
00194 }
00195 
00196 void callThread(Method<TestRequest, TestResponse>& m, volatile bool& done, bool& success, uint32_t start)
00197 {
00198   while (!done)
00199   {
00200     TestRequestPtr req(new TestRequest);
00201     req->value = start++;
00202     TestResponseConstPtr res = m.call(req);
00203     if (res->value != req->value * 2)
00204     {
00205       ROS_ERROR("Expected %d but got %d", req->value, res->value);
00206       success = false;
00207     }
00208   }
00209 }
00210 
00211 TEST(Intra, multipleCallerThreads)
00212 {
00213   ros::AsyncSpinner sp(1);
00214   sp.start();
00215   ros::NodeHandle nh;
00216   Server s("test", nh);
00217   s.addMethod<TestRequest, TestResponse>("double", doubleCallback);
00218   s.ready();
00219 
00220   Client c("test", nh);
00221   Method<TestRequest, TestResponse> m = c.addMethod<TestRequest, TestResponse>("double");
00222   c.connect();
00223 
00224   bool done = false;
00225   bool success = true;
00226   boost::thread_group tg;
00227   for (uint32_t i = 0; i < 10; ++i)
00228   {
00229     tg.create_thread(boost::bind(callThread, boost::ref(m), boost::ref(done), boost::ref(success), i * 10000));
00230   }
00231 
00232   ros::WallDuration(5.0).sleep();
00233   done = true;
00234   tg.join_all();
00235 
00236   ASSERT_TRUE(success);
00237 }
00238 
00239 TEST(Intra, addMethodLater)
00240 {
00241   ros::AsyncSpinner sp(1);
00242   sp.start();
00243   ros::NodeHandle nh;
00244   Server s("test", nh);
00245   s.ready();
00246 
00247   Client c("test", nh);
00248   c.connect();
00249 
00250   s.addMethod<TestRequest, TestResponse>("double", doubleCallback);
00251   Method<TestRequest, TestResponse> m = c.addMethod<TestRequest, TestResponse>("double");
00252 
00253   TestRequestPtr req(new TestRequest);
00254   req->value = 5;
00255   TestResponseConstPtr res = m.call(req);
00256   EXPECT_EQ(res->value, 10U);
00257 }
00258 
00259 TEST(Intra, multipleClientsSingleServer)
00260 {
00261   ros::AsyncSpinner sp(1);
00262   sp.start();
00263   ros::NodeHandle nh;
00264   Server s("test", nh);
00265   s.addMethod<TestRequest, TestResponse>("double", doubleCallback);
00266   s.ready();
00267 
00268   Client c1("test", nh);
00269   Method<TestRequest, TestResponse> m1 = c1.addMethod<TestRequest, TestResponse>("double");
00270   c1.connect();
00271 
00272   TestRequestPtr req(new TestRequest);
00273   req->value = 5;
00274   TestResponseConstPtr res = m1.call(req);
00275   EXPECT_EQ(res->value, 10U);
00276 
00277   Client c2("test", nh);
00278   Method<TestRequest, TestResponse> m2 = c2.addMethod<TestRequest, TestResponse>("double");
00279   c2.connect();
00280 
00281   res = m2.call(req);
00282   EXPECT_EQ(res->value, 10U);
00283 }
00284 
00285 struct AsyncCallHelper
00286 {
00287   AsyncCallHelper()
00288   : received(false)
00289   {}
00290 
00291   void cb(const MethodResponse<TestResponse>& res)
00292   {
00293     mr = res;
00294     response = res.response;
00295     received = true;
00296   }
00297 
00298   MethodResponse<TestResponse> mr;
00299   TestResponseConstPtr response;
00300   bool received;
00301 };
00302 
00303 TEST(Intra, callAsyncWithReturn)
00304 {
00305   ros::AsyncSpinner sp(1);
00306   sp.start();
00307   ros::NodeHandle nh;
00308   Server s("test", nh);
00309   s.addMethod<TestRequest, TestResponse>("double", doubleCallback);
00310   s.ready();
00311 
00312   Client c("test", nh);
00313   Method<TestRequest, TestResponse> m = c.addMethod<TestRequest, TestResponse>("double");
00314   c.connect();
00315 
00316   TestRequestPtr req(new TestRequest);
00317   req->value = 5;
00318   AsyncCallHelper h;
00319   m.callAsync(req, boost::bind(&AsyncCallHelper::cb, &h, _1));
00320 
00321   while (!h.received)
00322   {
00323     ros::WallDuration(0.01).sleep();
00324   }
00325 
00326   EXPECT_EQ(h.response->value, 10U);
00327 }
00328 
00329 struct AsyncResponseHelper
00330 {
00331   void cb(CallHandle<TestRequest, TestResponse>& handle)
00332   {
00333     handle_ = handle;
00334   }
00335 
00336   CallHandle<TestRequest, TestResponse> handle_;
00337 };
00338 
00339 TEST(Intra, callWithAsyncResponse)
00340 {
00341   ros::AsyncSpinner sp(1);
00342   sp.start();
00343   ros::NodeHandle nh;
00344   Server s("test", nh);
00345   AsyncResponseHelper arh;
00346   s.addMethod<TestRequest, TestResponse>("double", boost::bind(&AsyncResponseHelper::cb, &arh, _1));
00347   s.ready();
00348 
00349   Client c("test", nh);
00350   Method<TestRequest, TestResponse> m = c.addMethod<TestRequest, TestResponse>("double");
00351   c.connect();
00352 
00353   TestRequestPtr req(new TestRequest);
00354   req->value = 5;
00355   AsyncCallHelper h;
00356   m.callAsync(req, boost::bind(&AsyncCallHelper::cb, &h, _1));
00357 
00358   while (!arh.handle_)
00359   {
00360     ros::WallDuration(0.01).sleep();
00361   }
00362 
00363   TestResponsePtr res(new TestResponse);
00364   res->value = arh.handle_.getRequest()->value * 2;
00365   arh.handle_.respond(res);
00366 
00367   while (!h.received)
00368   {
00369     ros::WallDuration(0.01).sleep();
00370   }
00371 
00372   EXPECT_EQ(h.response->value, 10U);
00373 }
00374 
00375 TEST(Intra, callWithAsyncException)
00376 {
00377   ros::AsyncSpinner sp(1);
00378   sp.start();
00379   ros::NodeHandle nh;
00380   Server s("test", nh);
00381   AsyncResponseHelper arh;
00382   s.addMethod<TestRequest, TestResponse>("double", boost::bind(&AsyncResponseHelper::cb, &arh, _1));
00383   s.ready();
00384 
00385   Client c("test", nh);
00386   Method<TestRequest, TestResponse> m = c.addMethod<TestRequest, TestResponse>("double");
00387   c.connect();
00388 
00389   TestRequestPtr req(new TestRequest);
00390   req->value = 5;
00391   AsyncCallHelper h;
00392   m.callAsync(req, boost::bind(&AsyncCallHelper::cb, &h, _1));
00393 
00394   while (!arh.handle_)
00395   {
00396     ros::WallDuration(0.01).sleep();
00397   }
00398 
00399   arh.handle_.except("blah");
00400 
00401   while (!h.received)
00402   {
00403     ros::WallDuration(0.01).sleep();
00404   }
00405 
00406   EXPECT_EQ(h.mr.error_code, Response::EXCEPTION);
00407 }
00408 
00409 TEST(Intra, callWithNoResponse)
00410 {
00411   ros::AsyncSpinner sp(1);
00412   sp.start();
00413   ros::NodeHandle nh;
00414   Server s("test", nh);
00415   AsyncResponseHelper arh;
00416   s.addMethod<TestRequest, TestResponse>("double", boost::bind(&AsyncResponseHelper::cb, &arh, _1));
00417   s.ready();
00418 
00419   Client c("test", nh);
00420   Method<TestRequest, TestResponse> m = c.addMethod<TestRequest, TestResponse>("double");
00421   c.connect();
00422 
00423   TestRequestPtr req(new TestRequest);
00424   req->value = 5;
00425   AsyncCallHelper h;
00426   m.callAsync(req, boost::bind(&AsyncCallHelper::cb, &h, _1));
00427 
00428   while (!arh.handle_)
00429   {
00430     ros::WallDuration(0.01).sleep();
00431   }
00432 
00433   arh = AsyncResponseHelper();
00434 
00435   while (!h.received)
00436   {
00437     ros::WallDuration(0.01).sleep();
00438   }
00439 
00440   EXPECT_EQ(h.mr.error_code, Response::EXCEPTION);
00441 }
00442 
00443 int main(int argc, char** argv)
00444 {
00445   testing::InitGoogleTest(&argc, argv);
00446   ros::init(argc, argv, "test_intra");
00447   ros::NodeHandle nh;
00448 
00449   return RUN_ALL_TESTS();
00450 }


rve_rpc
Author(s): Josh Faust
autogenerated on Wed Dec 11 2013 14:30:53