00001
00023 #ifndef VIRTUAL_STIGMERGY_H_
00024 #define VIRTUAL_STIGMERGY_H_
00025
00026 #include <iostream>
00027 #include <vector>
00028 #include <map>
00029 #include <ros/ros.h>
00030
00031 #include "micros_swarm/random.h"
00032 #include "micros_swarm/singleton.h"
00033 #include "micros_swarm/runtime_handle.h"
00034 #include "micros_swarm/msg_queue_manager.h"
00035 #include "micros_swarm/packet_type.h"
00036 #include "micros_swarm/serialize.h"
00037 #include "gsdf_msgs/CommPacket.h"
00038 #include "gsdf_msgs/VirtualStigmergyQuery.h"
00039 #include "gsdf_msgs/VirtualStigmergyPut.h"
00040 #include "gsdf_msgs/VirtualStigmergyPuts.h"
00041
00042 namespace micros_swarm{
00043
00044 template<class Type>
00045 class VirtualStigmergy{
00046 public:
00047 VirtualStigmergy(){vstig_id_=-1;}
00048
00049 VirtualStigmergy(int vstig_id)
00050 {
00051 vstig_id_ = vstig_id;
00052 rth_ = Singleton<RuntimeHandle>::getSingleton();
00053 mqm_ = Singleton<MsgQueueManager>::getSingleton();
00054 rth_->createVirtualStigmergy(vstig_id_);
00055 robot_id_ = rth_->getRobotID();
00056 }
00057
00058 VirtualStigmergy(const VirtualStigmergy& vs)
00059 {
00060 rth_ = Singleton<RuntimeHandle>::getSingleton();
00061 mqm_ = Singleton<MsgQueueManager>::getSingleton();
00062 vstig_id_ = vs.vstig_id_;
00063 robot_id_ = vs.robot_id_;
00064 }
00065
00066 VirtualStigmergy& operator=(const VirtualStigmergy& vs)
00067 {
00068 if(this == &vs) {
00069 return *this;
00070 }
00071 rth_ = Singleton<RuntimeHandle>::getSingleton();
00072 mqm_ = Singleton<MsgQueueManager>::getSingleton();
00073 vstig_id_ = vs.vstig_id_;
00074 robot_id_ = vs.robot_id_;
00075 return *this;
00076 }
00077
00078 ~VirtualStigmergy()
00079 {
00080 rth_.reset();
00081 mqm_.reset();
00082 }
00083
00084 void put(const std::string& key, const Type& data)
00085 {
00086 std::vector<uint8_t> s = serialize_ros(data);
00087
00088 if(rth_->isVirtualStigmergyTupleExist(vstig_id_, key)) {
00089 VirtualStigmergyTuple vst;
00090 bool success = rth_->getVirtualStigmergyTuple(vstig_id_, key, vst);
00091 if(success) {
00092 rth_->insertOrUpdateVirtualStigmergy(vstig_id_, key, s, vst.lamport_clock + 1, time(NULL), 0, robot_id_);
00093 }
00094 }
00095 else {
00096 rth_->insertOrUpdateVirtualStigmergy(vstig_id_, key, s, 1, time(NULL), 0, robot_id_);
00097 }
00098
00099 VirtualStigmergyTuple local;
00100 bool success = rth_->getVirtualStigmergyTuple(vstig_id_, key, local);
00101 if(success) {
00102 gsdf_msgs::VirtualStigmergyPut vsp;
00103 vsp.vstig_id = vstig_id_;
00104 vsp.key = key;
00105 vsp.value = local.vstig_value;
00106 vsp.lamport_clock = local.lamport_clock;
00107 vsp.robot_id = robot_id_;
00108 std::vector<uint8_t> vsp_vec = serialize_ros(vsp);
00109
00110 gsdf_msgs::CommPacket p;
00111 p.header.source = rth_->getRobotID();
00112 p.header.type = VIRTUAL_STIGMERGY_PUT;
00113 p.header.data_len = vsp_vec.size();
00114 p.header.version = 1;
00115 p.header.checksum = 0;
00116 p.content.buf = vsp_vec;
00117 std::vector<uint8_t> msg_data = serialize_ros(p);
00118 mqm_->getOutMsgQueue("vstig")->push(msg_data);
00119 }
00120 }
00121
00122 Type get(const std::string& key)
00123 {
00124 VirtualStigmergyTuple vst;
00125 bool success = rth_->getVirtualStigmergyTuple(vstig_id_, key, vst);
00126
00127 if(!success) {
00128 std::cout<<"ID "<<vstig_id_<<" virtual stigmergy, "<<key<<" is not exist."<<std::endl;
00129 exit(-1);
00130 }
00131
00132 std::vector<uint8_t> data_vec = vst.vstig_value;
00133 Type data = deserialize_ros<Type>(data_vec);
00134
00135 rth_->updateVirtualStigmergyTupleReadCount(vstig_id_, key, vst.read_count+1);
00136 VirtualStigmergyTuple new_local;
00137 bool get_new_local = rth_->getVirtualStigmergyTuple(vstig_id_, key, new_local);
00138 if(get_new_local) {
00139
00140 double temperature = new_local.getTemperature();
00141 double rt = (double)rand()/RAND_MAX;
00142
00143 if(rt <= temperature) {
00144 gsdf_msgs::VirtualStigmergyQuery vsq;
00145 vsq.vstig_id = vstig_id_;
00146 vsq.key = key;
00147 vsq.value = new_local.vstig_value;
00148 vsq.lamport_clock = new_local.lamport_clock;
00149 vsq.robot_id = new_local.robot_id;
00150 std::vector<uint8_t> vsq_vec = serialize_ros(vsq);
00151
00152 gsdf_msgs::CommPacket p;
00153 p.header.source = robot_id_;
00154 p.header.type = VIRTUAL_STIGMERGY_QUERY;
00155 p.header.data_len = vsq_vec.size();
00156 p.header.version = 1;
00157 p.header.checksum = 0;
00158 p.content.buf = vsq_vec;
00159 std::vector<uint8_t> msg_data = serialize_ros(p);
00160 mqm_->getOutMsgQueue("vstig")->push(msg_data);
00161 }
00162 }
00163
00164 return data;
00165 }
00166
00167 void puts(const std::string& key, const Type& data)
00168 {
00169 std::vector<uint8_t> s = serialize_ros(data);
00170
00171 if(rth_->isVirtualStigmergyTupleExist(vstig_id_, key)) {
00172 VirtualStigmergyTuple vst;
00173 bool success = rth_->getVirtualStigmergyTuple(vstig_id_, key, vst);
00174 if(success) {
00175 rth_->insertOrUpdateVirtualStigmergy(vstig_id_, key, s, vst.lamport_clock + 1, time(NULL), 0, robot_id_);
00176 }
00177 }
00178 else {
00179 rth_->insertOrUpdateVirtualStigmergy(vstig_id_, key, s, 1, time(NULL), 0, robot_id_);
00180 }
00181
00182 VirtualStigmergyTuple local;
00183 bool success = rth_->getVirtualStigmergyTuple(vstig_id_, key, local);
00184 if(success) {
00185 gsdf_msgs::VirtualStigmergyPuts vsps;
00186 vsps.vstig_id = vstig_id_;
00187 vsps.key = key;
00188 vsps.value = local.vstig_value;
00189 vsps.lamport_clock = local.lamport_clock;
00190 vsps.robot_id = robot_id_;
00191 int neighbor_size = rth_->getNeighborSize();
00192 if(neighbor_size < 3) {
00193 vsps.prob = 1.0;
00194 }
00195 else {
00196 vsps.prob = 2.0/neighbor_size;
00197 }
00198
00199 std::vector<uint8_t> vsps_vec = serialize_ros(vsps);
00200
00201 gsdf_msgs::CommPacket p;
00202 p.header.source = rth_->getRobotID();
00203 p.header.type = VIRTUAL_STIGMERGY_PUTS;
00204 p.header.data_len = vsps_vec.size();
00205 p.header.version = 1;
00206 p.header.checksum = 0;
00207 p.content.buf = vsps_vec;
00208 std::vector<uint8_t> msg_data = serialize_ros(p);
00209 mqm_->getOutMsgQueue("vstig")->push(msg_data);
00210 }
00211 }
00212
00213 Type gets(const std::string& key)
00214 {
00215 VirtualStigmergyTuple vst;
00216 bool success = rth_->getVirtualStigmergyTuple(vstig_id_, key, vst);
00217
00218 if(!success) {
00219 std::cout<<"ID "<<vstig_id_<<" virtual stigmergy, "<<key<<" is not exist."<<std::endl;
00220 exit(-1);
00221 }
00222
00223 std::vector<uint8_t> data_vec = vst.vstig_value;
00224 Type data = deserialize_ros<Type>(data_vec);
00225
00226 return data;
00227 }
00228
00229 void remove(const std::string& key)
00230 {
00231 rth_->deleteVirtualStigmergyValue(vstig_id_, key);
00232 }
00233
00234 int size()
00235 {
00236 return rth_->getVirtualStigmergySize(vstig_id_);
00237 }
00238
00239 void print()
00240 {
00241 rth_->printVirtualStigmergy();
00242 }
00243 private:
00244 int vstig_id_;
00245 int robot_id_;
00246 boost::shared_ptr<RuntimeHandle> rth_;
00247 boost::shared_ptr<micros_swarm::MsgQueueManager> mqm_;
00248 };
00249 }
00250 #endif