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
00040 #include "roscpp_sessions/simple_session.h"
00041 #include "roscpp_sessions/set_variable.h"
00042 #include "roscpp_sessions/get_variable.h"
00043 #include "roscpp_sessions/add_variables.h"
00044
00045 #include <map>
00046
00047 using namespace std;
00048 using namespace ros;
00049
00050
00051 class SimpleSessionInstance
00052 {
00053 public:
00054 void set_variable(const string& name, int val) { variables[name] = val; }
00055 int get_variable(const string& name) {
00056 ROS_ASSERT(variables.find(name)!=variables.end());
00057 return variables[name];
00058 }
00059 void add_variables(const string& result, const string& name1, const string& name2) {
00060 ROS_ASSERT(variables.find(name1)!=variables.end());
00061 ROS_ASSERT(variables.find(name2)!=variables.end());
00062 variables[result] = variables[name1] + variables[name2];
00063 }
00064
00065 private:
00066 map<string,int> variables;
00067 };
00068
00069 class SimpleSession : public ros::Node
00070 {
00071 string _sessionname;
00072 public:
00073 SimpleSession() : ros::Node("simple_session")
00074 {
00075 advertiseService("session_adv",&SimpleSession::startsession,this,1);
00076 _sessionname = mapName("session_adv");
00077
00078
00079 advertiseService("set_variable",&SimpleSession::set_variable,this,-1);
00080 advertiseService("get_variable",&SimpleSession::get_variable,this,-1);
00081 advertiseService("add_variables",&SimpleSession::add_variables,this,-1);
00082 }
00083
00084 template <class MReq>
00085 SimpleSessionInstance* getstate(const MReq& req)
00086 {
00087 if( !req.__connection_header )
00088 return NULL;
00089
00090 ros::M_string::const_iterator it = req.__connection_header->find(_sessionname);
00091 if( it == req.__connection_header->end() ) {
00092 ROS_WARN("failed to find header key %s\n",_sessionname.c_str());
00093 return NULL;
00094 }
00095
00096 boost::mutex::scoped_lock lock(map_mutex);
00097
00098 int sessionid = atoi(it->second.c_str());
00099 if( mapsessions.find(sessionid) == mapsessions.end() ) {
00100 ROS_WARN("failed to find session id %d\n", sessionid);
00101 return NULL;
00102 }
00103 return mapsessions[sessionid].get();
00104 }
00105
00106 bool startsession(roscpp_sessions::simple_session::Request& req, roscpp_sessions::simple_session::Response& res) {
00107 if( req.sessionid ) {
00108
00109 int success = mapsessions.erase(req.sessionid)>0;
00110 cout << "terminate session: " << req.sessionid << ", success: " << success << endl;
00111 }
00112 else {
00113
00114 int id = rand();
00115 ROS_ASSERT( mapsessions.find(id) == mapsessions.end() );
00116 mapsessions[id].reset(new SimpleSessionInstance());
00117 cout << "simple session " << id << " started with options " << req.options << endl;
00118 res.sessionid = id;
00119 }
00120 return true;
00121 }
00122
00123 bool set_variable(roscpp_sessions::set_variable::Request& req,
00124 roscpp_sessions::set_variable::Response& res)
00125 {
00126 SimpleSessionInstance* pinst = getstate(req);
00127 if( pinst == NULL )
00128 return false;
00129 pinst->set_variable(req.variable,req.value);
00130 return true;
00131 }
00132
00133 bool get_variable(roscpp_sessions::get_variable::Request& req,
00134 roscpp_sessions::get_variable::Response& res)
00135 {
00136 SimpleSessionInstance* pinst = getstate(req);
00137 if( pinst == NULL )
00138 return false;
00139 res.result = pinst->get_variable(req.variable);
00140 return true;
00141 }
00142
00143 bool add_variables(roscpp_sessions::add_variables::Request& req,
00144 roscpp_sessions::add_variables::Response& res)
00145 {
00146 SimpleSessionInstance* pinst = getstate(req);
00147 if( pinst == NULL )
00148 return false;
00149 pinst->add_variables(req.result, req.variable1,req.variable2);
00150 return true;
00151 }
00152
00153 private:
00154 map<int,boost::shared_ptr<SimpleSessionInstance> > mapsessions;
00155 boost::mutex map_mutex;
00156 };
00157
00158 int main(int argc, char **argv)
00159 {
00160 ros::init(argc, argv);
00161 SimpleSession session;
00162 session.spin();
00163
00164 return 0;
00165 }