session_call.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2008, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  */
00034 
00035 // author: Rosen Diankov
00036 #include <gtest/gtest.h>
00037 
00038 #include <ros/node.h>
00039 #include <ros/session.h>
00040 #include <boost/thread/mutex.hpp>
00041 #include <boost/thread/thread.hpp>
00042 #include <boost/shared_ptr.hpp>
00043 #include <boost/bind.hpp>
00044 
00045 #include <ros/message.h>
00046 #include "roscpp_sessions/simple_session.h"
00047 #include "roscpp_sessions/set_variable.h"
00048 #include "roscpp_sessions/get_variable.h"
00049 #include "roscpp_sessions/add_variables.h"
00050 
00051 #include <map>
00052 #include <list>
00053 
00054 using namespace std;
00055 using namespace ros;
00056 
00057 TEST(SessionCall, CreateTerminate)
00058 {
00059     roscpp_sessions::simple_session::Request req;
00060     roscpp_sessions::simple_session::Response res;
00061     req.options = 1234;
00062     session::abstractSessionHandle handle = session::create_session("session_adv",req,res);
00063     ASSERT_TRUE(handle != NULL);
00064     ASSERT_TRUE(handle->GetSessionId() != 0 );
00065 
00066     fprintf(stderr,"session %s:%d open\n", handle->GetSessionName().c_str(), handle->GetSessionId());
00067 
00068     fprintf(stderr, "terminating first\n");
00069     handle->terminate();
00070     handle.reset();
00071 
00072     handle = session::create_session("session_adv",req,res);
00073     ASSERT_TRUE(!!handle);
00074     ASSERT_TRUE(handle->GetSessionId() != 0 );
00075 
00076     fprintf(stderr, "session %s:%d open\n", handle->GetSessionName().c_str(), handle->GetSessionId());
00077 
00078     fprintf(stderr, "deleting\n");
00079     handle.reset();
00080 }
00081 
00082 TEST(SessionCall, CreateTerminateComplex)
00083 {
00084     const int N = 20;
00085     session::abstractSessionHandle handles[N];
00086     roscpp_sessions::simple_session::Request req;
00087     roscpp_sessions::simple_session::Response res;
00088     roscpp_sessions::set_variable::Request setreq;
00089     roscpp_sessions::set_variable::Response setres;
00090     roscpp_sessions::get_variable::Request getreq;
00091     roscpp_sessions::get_variable::Response getres;
00092 
00093     for(int i = 0; i < N; ++i) {
00094         req.options = i;
00095         handles[i] = session::create_session("session_adv",req,res);
00096         ASSERT_TRUE(!!handles[i]);
00097         ASSERT_TRUE(handles[i]->GetSessionId() != 0 );
00098     }
00099 
00100     for(int iter = 0; iter < 10; ++iter ) {
00101         for(int i = 0; i < N; ++i) {
00102             setreq.variable = "asdf";
00103             setreq.value = i;
00104             handles[i]->call("set_variable",setreq,setres);
00105         }
00106 
00107         for(int i = 0; i < N; ++i) {
00108             getreq.variable = "asdf";
00109             handles[i]->call("get_variable",getreq,getres);
00110             EXPECT_EQ(i, getres.result);
00111         }
00112 
00113         // do again but this time asynchronously
00114         for(int i = 0; i < N; ++i) {
00115             setreq.variable = "asdf";
00116             setreq.value = i*i;
00117             handles[i]->call("set_variable",setreq,setres,true);
00118         }
00119 
00120         for(int i = 0; i < N; ++i) {
00121             getreq.variable = "asdf";
00122             handles[i]->call("get_variable",getreq,getres);
00123             EXPECT_EQ(i*i, getres.result);
00124             ROS_ASSERT(i*i == getres.result);
00125         }
00126     }
00127 
00128     for(int i = 1; i < N; ++i)
00129         handles[i].reset();
00130 
00131     setreq.variable = "hmmmm";
00132     setreq.value = 1234;
00133     handles[0]->call("set_variable",setreq,setres,true);
00134     getreq.variable = "hmmmm";
00135     handles[0]->call("get_variable",getreq,getres);
00136     EXPECT_EQ(1234, getres.result);
00137     handles[0].reset();
00138 }
00139 
00140 TEST(SessionCall, CreateSyncCommands)
00141 {
00142     roscpp_sessions::simple_session::Request req;
00143     roscpp_sessions::simple_session::Response res;
00144     req.options = 1234;
00145     session::abstractSessionHandle handle = session::create_session("session_adv",req,res);
00146     ASSERT_TRUE(!!handle);
00147 
00148     roscpp_sessions::set_variable::Request setreq;
00149     roscpp_sessions::set_variable::Response setres;
00150     roscpp_sessions::get_variable::Request getreq;
00151     roscpp_sessions::get_variable::Response getres;
00152     roscpp_sessions::add_variables::Request addreq;
00153     roscpp_sessions::add_variables::Response addres;
00154 
00155     int N = 100;
00156     for(int i = 0; i < N; ++i) {
00157         int a = rand(), b = rand(), c = a+b;
00158         setreq.variable = "a";
00159         setreq.value = a;
00160         handle->call("set_variable",setreq,setres);
00161 
00162         setreq.variable = "b";
00163         setreq.value = b;
00164         handle->call("set_variable",setreq,setres);
00165 
00166         getreq.variable = "a";
00167         handle->call("get_variable",getreq,getres);
00168         EXPECT_EQ(a,getres.result);
00169 
00170         addreq.variable1 = "a";
00171         addreq.variable2 = "b";
00172         addreq.result = "c";
00173         handle->call("add_variables",addreq,addres);
00174 
00175         getreq.variable = "c";
00176         handle->call("get_variable",getreq,getres);
00177         EXPECT_EQ(c,getres.result);
00178     }
00179 }
00180 
00181 TEST(SessionCall, CreateAsyncCommands)
00182 {
00183     roscpp_sessions::simple_session::Request req;
00184     roscpp_sessions::simple_session::Response res;
00185     req.options = 1234;
00186     session::abstractSessionHandle handle = session::create_session("session_adv",req,res);
00187     ASSERT_TRUE(!!handle);
00188 
00189     roscpp_sessions::set_variable::Request setreq;
00190     roscpp_sessions::set_variable::Response setres;
00191     roscpp_sessions::get_variable::Request getreq;
00192     roscpp_sessions::get_variable::Response getres;
00193     roscpp_sessions::add_variables::Request addreq;
00194     roscpp_sessions::add_variables::Response addres;
00195 
00196     // should complete relatively fast
00197     int N = 2000;
00198     for(int i = 0; i < N; ++i) {
00199         int a = rand(), b = rand();
00200         setreq.variable = "a";
00201         setreq.value = a;
00202         handle->call("set_variable",setreq,setres,true);
00203 
00204         setreq.variable = "b";
00205         setreq.value = b;
00206         handle->call("set_variable",setreq,setres,true);
00207     }
00208 
00209     N = 100;
00210     for(int i = 0; i < N; ++i) {
00211         int a = rand(), b = rand(), c = a+b;
00212         setreq.variable = "a";
00213         setreq.value = a;
00214         handle->call("set_variable",setreq,setres,true);
00215 
00216         setreq.variable = "b";
00217         setreq.value = b;
00218         handle->call("set_variable",setreq,setres,true);
00219 
00220         getreq.variable = "a";
00221         handle->call("get_variable",getreq,getres);
00222         EXPECT_EQ(a,getres.result);
00223 
00224         addreq.variable1 = "a";
00225         addreq.variable2 = "b";
00226         addreq.result = "c";
00227         handle->call("add_variables",addreq,addres,true);
00228 
00229         getreq.variable = "c";
00230         handle->call("get_variable",getreq,getres);
00231         EXPECT_EQ(c,getres.result);
00232     }
00233 
00234     handle->terminate();
00235     handle->terminate();
00236     handle->terminate();
00237 }
00238 
00239 TEST(SessionCall, SyncCommandsTerm)
00240 {
00241     roscpp_sessions::simple_session::Request req;
00242     roscpp_sessions::simple_session::Response res;
00243     req.options = 1234;
00244     session::abstractSessionHandle handle = session::create_session("session_adv",req,res);
00245     ASSERT_TRUE(!!handle);
00246 
00247     roscpp_sessions::set_variable::Request setreq;
00248     roscpp_sessions::set_variable::Response setres;
00249     roscpp_sessions::get_variable::Request getreq;
00250     roscpp_sessions::get_variable::Response getres;
00251     roscpp_sessions::add_variables::Request addreq;
00252     roscpp_sessions::add_variables::Response addres;
00253 
00254     int N = 100;
00255     for(int i = 0; i < N; ++i) {
00256         int a = rand(), b = rand(), c = a+b;
00257         setreq.variable = "a";
00258         setreq.value = a;
00259         handle->call("set_variable",setreq,setres);
00260 
00261         setreq.variable = "b";
00262         setreq.value = b;
00263         handle->call("set_variable",setreq,setres);
00264 
00265         getreq.variable = "a";
00266         handle->call("get_variable",getreq,getres);
00267         ASSERT_TRUE(getres.result==a);
00268 
00269         addreq.variable1 = "a";
00270         addreq.variable2 = "b";
00271         addreq.result = "c";
00272         handle->call("add_variables",addreq,addres);
00273 
00274         getreq.variable = "c";
00275         handle->call("get_variable",getreq,getres);
00276         ASSERT_TRUE(getres.result==c);
00277     }
00278 
00279     session::abstractSessionHandle pnewhandle(new session::Session<roscpp_sessions::simple_session::Request, roscpp_sessions::simple_session::Response>(handle->GetSessionName(), handle->GetSessionId()));
00280     handle = pnewhandle;
00281 
00282     for(int i = 0; i < N; ++i) {
00283         int a = rand(), b = rand(), c = a+b;
00284         setreq.variable = "a";
00285         setreq.value = a;
00286         handle->call("set_variable",setreq,setres);
00287 
00288         setreq.variable = "b";
00289         setreq.value = b;
00290         handle->call("set_variable",setreq,setres);
00291 
00292         getreq.variable = "a";
00293         handle->call("get_variable",getreq,getres);
00294         ASSERT_TRUE(getres.result==a);
00295 
00296         addreq.variable1 = "a";
00297         addreq.variable2 = "b";
00298         addreq.result = "c";
00299         handle->call("add_variables",addreq,addres);
00300 
00301         getreq.variable = "c";
00302         handle->call("get_variable",getreq,getres);
00303         ASSERT_TRUE(getres.result==c);
00304     }
00305 
00306     ASSERT_TRUE(handle->terminate());
00307 }
00308 
00309 void testsynccommandsterm(bool& bsuccess)
00310 {
00311     bsuccess = false;
00312     roscpp_sessions::simple_session::Request req;
00313     roscpp_sessions::simple_session::Response res;
00314     req.options = 1234;
00315     session::abstractSessionHandle handle = session::create_session("session_adv",req,res);
00316     if( handle == NULL ) {
00317         fprintf(stderr, "failed to create handle\n");
00318         return;
00319     }
00320 
00321     roscpp_sessions::set_variable::Request setreq;
00322     roscpp_sessions::set_variable::Response setres;
00323     roscpp_sessions::get_variable::Request getreq;
00324     roscpp_sessions::get_variable::Response getres;
00325     roscpp_sessions::add_variables::Request addreq;
00326     roscpp_sessions::add_variables::Response addres;
00327 
00328     int N = 100;
00329     for(int i = 0; i < N; ++i) {
00330         int a = rand(), b = rand(), c = a+b;
00331         setreq.variable = "a";
00332         setreq.value = a;
00333         handle->call("set_variable",setreq,setres);
00334 
00335         setreq.variable = "b";
00336         setreq.value = b;
00337         handle->call("set_variable",setreq,setres);
00338 
00339         getreq.variable = "a";
00340         handle->call("get_variable",getreq,getres);
00341         if(getres.result!=a) {
00342             fprintf(stderr, "a not correct\n");
00343             return;
00344         }
00345 
00346         addreq.variable1 = "a";
00347         addreq.variable2 = "b";
00348         addreq.result = "c";
00349         handle->call("add_variables",addreq,addres);
00350 
00351         getreq.variable = "c";
00352         handle->call("get_variable",getreq,getres);
00353         if(getres.result!=c) {
00354             fprintf(stderr, "c not correct\n");
00355             return;
00356         }
00357     }
00358 
00359     if( !handle->terminate() )
00360         return;
00361 
00362     bsuccess = true;
00363 }
00364 
00365 TEST(SessionCall, MultiSessions)
00366 {
00367     roscpp_sessions::simple_session::Request req;
00368     roscpp_sessions::simple_session::Response res;
00369     req.options = 1234;
00370     session::abstractSessionHandle handle = session::create_session("session_adv",req,res);
00371     ASSERT_TRUE(!!handle);
00372     handle.reset();
00373 
00374     // create multiple threads of sessions
00375     list<boost::thread*> listthreads;
00376     list<bool> listsuccess;
00377     for(int i = 0; i < 20; ++i) {
00378         listsuccess.push_back(false);
00379         listthreads.push_back(new boost::thread(boost::bind(testsynccommandsterm,boost::ref(listsuccess.back()))));
00380     }
00381 
00382     // wait on all threads
00383     list<bool>::iterator itsuccess = listsuccess.begin();
00384     for(list<boost::thread*>::iterator it = listthreads.begin(); it != listthreads.end(); ++it, ++itsuccess) {
00385         (*it)->join();
00386         ASSERT_TRUE(*itsuccess);
00387         delete *it;
00388     }
00389 }
00390 
00391 int main(int argc, char** argv)
00392 {
00393     testing::InitGoogleTest(&argc, argv);
00394 
00395     ros::init(argc, argv);
00396     ros::Node n("caller");
00397 
00398     ros::service::waitForService("session_adv");
00399     int ret = RUN_ALL_TESTS();
00400 
00401     
00402 
00403     return ret;
00404 }
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


roscpp_sessions
Author(s): Rosen Diankov (rdiankov@cs.cmu.edu)
autogenerated on Sat Mar 23 2013 13:53:29