Go to the documentation of this file.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
00029
00030
00031
00032
00033
00034
00035
00036 #include <ros/node.h>
00037 #include <ros/session.h>
00038 #include <boost/thread/mutex.hpp>
00039 #include <boost/shared_ptr.hpp>
00040
00041 #include "roscpp_sessions/simple_session.h"
00042 #include "roscpp_sessions/set_variable.h"
00043 #include "roscpp_sessions/get_variable.h"
00044 #include "roscpp_sessions/add_variables.h"
00045
00046 using namespace std;
00047 using namespace ros;
00048
00049 class SimpleSessionClient
00050 {
00051 public:
00052 SimpleSessionClient()
00053 {
00054 roscpp_sessions::simple_session::Request req;
00055 roscpp_sessions::simple_session::Response res;
00056 req.options = 1234;
00057 handle = session::create_session("session_adv",req,res);
00058
00059 if( !!handle ) {
00060 printf("session %s:%d open\n", handle->GetSessionName().c_str(), handle->GetSessionId());
00061 test();
00062
00063 printf("closing all connections and resuming session\n");
00064 session::abstractSessionHandle pnewhandle(new session::Session<roscpp_sessions::simple_session::Request, roscpp_sessions::simple_session::Response>(handle->GetSessionName(), handle->GetSessionId()));
00065 handle = pnewhandle;
00066 test();
00067
00068 handle->terminate();
00069 }
00070 }
00071
00072 void test() {
00073 int N = 100;
00074 for(int i = 0; i < N; ++i) {
00075 int a = rand(), b = rand(), c = a+b;
00076 setreq.variable = "a";
00077 setreq.value = a;
00078 if( !handle->call("set_variable",setreq,setres) ) {
00079 printf("failed to call set_variable");
00080 return;
00081 }
00082
00083 setreq.variable = "b";
00084 setreq.value = b;
00085 if( !handle->call("set_variable",setreq,setres) ) {
00086 printf("failed to call set_variable");
00087 return;
00088 }
00089
00090 getreq.variable = "a";
00091 if( !handle->call("get_variable",getreq,getres) ) {
00092 printf("failed to call get_variable");
00093 return;
00094 }
00095 ROS_ASSERT(getres.result==a);
00096
00097 addreq.variable1 = "a";
00098 addreq.variable2 = "b";
00099 addreq.result = "c";
00100 if( !handle->call("add_variables",addreq,addres) ) {
00101 printf("failed to call add_variables");
00102 return;
00103 }
00104
00105 getreq.variable = "c";
00106 if( !handle->call("get_variable",getreq,getres) ) {
00107 printf("failed to call get_variable");
00108 return;
00109 }
00110
00111 printf("%d + %d = %d(res=%d)", a, b, c, getres.result);
00112 ROS_ASSERT(getres.result==c);
00113 }
00114 }
00115
00116 private:
00117 session::abstractSessionHandle handle;
00118 roscpp_sessions::set_variable::Request setreq;
00119 roscpp_sessions::set_variable::Response setres;
00120 roscpp_sessions::get_variable::Request getreq;
00121 roscpp_sessions::get_variable::Response getres;
00122 roscpp_sessions::add_variables::Request addreq;
00123 roscpp_sessions::add_variables::Response addres;
00124 };
00125
00126 int
00127 main(int argc, char** argv)
00128 {
00129 ros::init(argc, argv);
00130 ros::Node n("caller");
00131
00132 ros::service::waitForService("mysession");
00133
00134 struct timespec sleep_time = {0, 2000000};
00135 while(n.ok()) {
00136 SimpleSessionClient client;
00137 nanosleep(&sleep_time,NULL);
00138 }
00139
00140
00141 return 0;
00142 }