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_handle.h>
00037 #include <ros/master.h>
00038 #include <ros/session.h>
00039 #include <boost/thread/mutex.hpp>
00040 #include <boost/shared_ptr.hpp>
00041
00042 #include "session_tutorials/simple_session.h"
00043 #include "session_tutorials/set_variable.h"
00044 #include "session_tutorials/get_variable.h"
00045 #include "session_tutorials/add_variables.h"
00046 #include <map>
00047
00048 using namespace std;
00049 using namespace ros;
00050
00051 boost::shared_ptr<ros::NodeHandle> s_pmasternode;
00052
00053 class SimpleSessionClient
00054 {
00055 public:
00056 SimpleSessionClient()
00057 {
00058 session_tutorials::simple_session::Request req;
00059 session_tutorials::simple_session::Response res;
00060 req.options = 1234;
00061 handle = session::create_session("simple_session",req,res);
00062
00063 ROS_INFO("session %s:%d open", handle->GetSessionName().c_str(), handle->GetSessionId());
00064 testsync();
00065 testasync();
00066
00067 ROS_INFO("closing all connections and resuming session");
00068 session::abstractSessionHandle newhandle(new session::Session<session_tutorials::simple_session::Request, session_tutorials::simple_session::Response>(handle->GetSessionName(), handle->GetSessionId()));
00069 handle = newhandle;
00070 testsync();
00071
00072 handle->terminate();
00073 handle.reset();
00074 }
00075
00076 void testasync() {
00077 Time start_time = Time::now();
00078 int N = 10000;
00079 for(int i = 0; i < N; ++i) {
00080 int a = rand(), b = rand();
00081 setreq.variable = "a";
00082 setreq.value = a;
00083 handle->call("set_variable",setreq,setres,true);
00084
00085 setreq.variable = "b";
00086 setreq.value = b;
00087 handle->call("set_variable",setreq,setres,true);
00088 }
00089
00090 ROS_INFO("made %d async calls in %fs", 2*N,(float)(Time::now()-start_time).toSec());
00091
00092
00093 getreq.variable = "a";
00094 handle->call("get_variable",getreq,getres);
00095 ROS_INFO("flushed all async calls");
00096 }
00097
00098 void testsync() {
00099 Time start_time = Time::now();
00100 int N = 5000;
00101 for(int i = 0; i < N; ++i) {
00102 int a = rand(), b = rand(), c = a+b;
00103 setreq.variable = "a";
00104 setreq.value = a;
00105 handle->call("set_variable",setreq,setres);
00106
00107 setreq.variable = "b";
00108 setreq.value = b;
00109 handle->call("set_variable",setreq,setres);
00110
00111 getreq.variable = "a";
00112 handle->call("get_variable",getreq,getres);
00113 ROS_ASSERT(getres.result==a);
00114
00115
00116 addreq.variable1 = "a";
00117 addreq.variable2 = "b";
00118 addreq.result = "c";
00119 handle->call("add_variables",addreq,addres);
00120
00121 getreq.variable = "c";
00122 handle->call("get_variable",getreq,getres);
00123
00124 ROS_ASSERT(getres.result==c);
00125
00126 }
00127
00128 ROS_INFO("made %d sync calls in %fs", 5*N,(float)(Time::now()-start_time).toSec());
00129 }
00130
00131 private:
00132 session::abstractSessionHandle handle;
00133 session_tutorials::set_variable::Request setreq;
00134 session_tutorials::set_variable::Response setres;
00135 session_tutorials::get_variable::Request getreq;
00136 session_tutorials::get_variable::Response getres;
00137 session_tutorials::add_variables::Request addreq;
00138 session_tutorials::add_variables::Response addres;
00139 };
00140
00141 int main(int argc, char **argv)
00142 {
00143 ros::init(argc, argv,"simple_session_client");
00144
00145 s_pmasternode.reset(new ros::NodeHandle());
00146 if( !ros::master::check() )
00147 return 1;
00148
00149 boost::shared_ptr<SimpleSessionClient> client(new SimpleSessionClient());
00150 ros::spin();
00151 client.reset();
00152 s_pmasternode.reset();
00153 return 0;
00154 }