virtual_stigmergy.h
Go to the documentation of this file.
1 
23 #ifndef VIRTUAL_STIGMERGY_H_
24 #define VIRTUAL_STIGMERGY_H_
25 
26 #include <iostream>
27 #include <vector>
28 #include <map>
29 #include <ros/ros.h>
30 
31 #include "micros_swarm/random.h"
32 #include "micros_swarm/singleton.h"
36 #include "micros_swarm/serialize.h"
37 #include "gsdf_msgs/CommPacket.h"
38 #include "gsdf_msgs/VirtualStigmergyQuery.h"
39 #include "gsdf_msgs/VirtualStigmergyPut.h"
40 #include "gsdf_msgs/VirtualStigmergyPuts.h"
41 
42 namespace micros_swarm{
43 
44  template<class Type>
46  public:
48 
49  VirtualStigmergy(int vstig_id)
50  {
51  vstig_id_ = vstig_id;
54  rth_->createVirtualStigmergy(vstig_id_);
55  robot_id_ = rth_->getRobotID();
56  }
57 
59  {
62  vstig_id_ = vs.vstig_id_;
63  robot_id_ = vs.robot_id_;
64  }
65 
67  {
68  if(this == &vs) {
69  return *this;
70  }
73  vstig_id_ = vs.vstig_id_;
74  robot_id_ = vs.robot_id_;
75  return *this;
76  }
77 
79  {
80  rth_.reset();
81  mqm_.reset();
82  }
83 
84  void put(const std::string& key, const Type& data)
85  {
86  std::vector<uint8_t> s = serialize_ros(data);
87 
88  if(rth_->isVirtualStigmergyTupleExist(vstig_id_, key)) {
90  bool success = rth_->getVirtualStigmergyTuple(vstig_id_, key, vst);
91  if(success) {
92  rth_->insertOrUpdateVirtualStigmergy(vstig_id_, key, s, vst.lamport_clock + 1, time(NULL), 0, robot_id_);
93  }
94  }
95  else {
96  rth_->insertOrUpdateVirtualStigmergy(vstig_id_, key, s, 1, time(NULL), 0, robot_id_);
97  }
98 
100  bool success = rth_->getVirtualStigmergyTuple(vstig_id_, key, local);
101  if(success) {
102  gsdf_msgs::VirtualStigmergyPut vsp;
103  vsp.vstig_id = vstig_id_;
104  vsp.key = key;
105  vsp.value = local.vstig_value;
106  vsp.lamport_clock = local.lamport_clock;
107  vsp.robot_id = robot_id_;
108  std::vector<uint8_t> vsp_vec = serialize_ros(vsp);
109 
110  gsdf_msgs::CommPacket p;
111  p.header.source = rth_->getRobotID();
112  p.header.type = VIRTUAL_STIGMERGY_PUT;
113  p.header.data_len = vsp_vec.size();
114  p.header.version = 1;
115  p.header.checksum = 0;
116  p.content.buf = vsp_vec;
117  std::vector<uint8_t> msg_data = serialize_ros(p);
118  mqm_->getOutMsgQueue("vstig")->push(msg_data);
119  }
120  }
121 
122  Type get(const std::string& key)
123  {
125  bool success = rth_->getVirtualStigmergyTuple(vstig_id_, key, vst);
126 
127  if(!success) {
128  std::cout<<"ID "<<vstig_id_<<" virtual stigmergy, "<<key<<" is not exist."<<std::endl;
129  exit(-1);
130  }
131 
132  std::vector<uint8_t> data_vec = vst.vstig_value;
133  Type data = deserialize_ros<Type>(data_vec);
134 
135  rth_->updateVirtualStigmergyTupleReadCount(vstig_id_, key, vst.read_count+1);
136  VirtualStigmergyTuple new_local;
137  bool get_new_local = rth_->getVirtualStigmergyTuple(vstig_id_, key, new_local);
138  if(get_new_local) {
139  //cold-hot dada distinction
140  double temperature = new_local.getTemperature();
141  double rt = (double)rand()/RAND_MAX;
142  //std::cout<<"<<"<<temperature<<", "<<rt<<">>"<<std::endl;
143  if(rt <= temperature) {
144  gsdf_msgs::VirtualStigmergyQuery vsq;
145  vsq.vstig_id = vstig_id_;
146  vsq.key = key;
147  vsq.value = new_local.vstig_value;
148  vsq.lamport_clock = new_local.lamport_clock;
149  vsq.robot_id = new_local.robot_id;
150  std::vector<uint8_t> vsq_vec = serialize_ros(vsq);
151 
152  gsdf_msgs::CommPacket p;
153  p.header.source = robot_id_;
154  p.header.type = VIRTUAL_STIGMERGY_QUERY;
155  p.header.data_len = vsq_vec.size();
156  p.header.version = 1;
157  p.header.checksum = 0;
158  p.content.buf = vsq_vec;
159  std::vector<uint8_t> msg_data = serialize_ros(p);
160  mqm_->getOutMsgQueue("vstig")->push(msg_data);
161  }
162  }
163 
164  return data;
165  }
166 
167  void puts(const std::string& key, const Type& data)
168  {
169  std::vector<uint8_t> s = serialize_ros(data);
170 
171  if(rth_->isVirtualStigmergyTupleExist(vstig_id_, key)) {
173  bool success = rth_->getVirtualStigmergyTuple(vstig_id_, key, vst);
174  if(success) {
175  rth_->insertOrUpdateVirtualStigmergy(vstig_id_, key, s, vst.lamport_clock + 1, time(NULL), 0, robot_id_);
176  }
177  }
178  else {
179  rth_->insertOrUpdateVirtualStigmergy(vstig_id_, key, s, 1, time(NULL), 0, robot_id_);
180  }
181 
182  VirtualStigmergyTuple local;
183  bool success = rth_->getVirtualStigmergyTuple(vstig_id_, key, local);
184  if(success) {
185  gsdf_msgs::VirtualStigmergyPuts vsps;
186  vsps.vstig_id = vstig_id_;
187  vsps.key = key;
188  vsps.value = local.vstig_value;
189  vsps.lamport_clock = local.lamport_clock;
190  vsps.robot_id = robot_id_;
191  int neighbor_size = rth_->getNeighborSize();
192  if(neighbor_size < 3) {
193  vsps.prob = 1.0;
194  }
195  else {
196  vsps.prob = 2.0/neighbor_size;
197  }
198 
199  std::vector<uint8_t> vsps_vec = serialize_ros(vsps);
200 
201  gsdf_msgs::CommPacket p;
202  p.header.source = rth_->getRobotID();
203  p.header.type = VIRTUAL_STIGMERGY_PUTS;
204  p.header.data_len = vsps_vec.size();
205  p.header.version = 1;
206  p.header.checksum = 0;
207  p.content.buf = vsps_vec;
208  std::vector<uint8_t> msg_data = serialize_ros(p);
209  mqm_->getOutMsgQueue("vstig")->push(msg_data);
210  }
211  }
212 
213  Type gets(const std::string& key)
214  {
216  bool success = rth_->getVirtualStigmergyTuple(vstig_id_, key, vst);
217 
218  if(!success) {
219  std::cout<<"ID "<<vstig_id_<<" virtual stigmergy, "<<key<<" is not exist."<<std::endl;
220  exit(-1);
221  }
222 
223  std::vector<uint8_t> data_vec = vst.vstig_value;
224  Type data = deserialize_ros<Type>(data_vec);
225 
226  return data;
227  }
228 
229  void remove(const std::string& key)
230  {
231  rth_->deleteVirtualStigmergyValue(vstig_id_, key);
232  }
233 
234  int size()
235  {
236  return rth_->getVirtualStigmergySize(vstig_id_);
237  }
238 
239  void print()
240  {
241  rth_->printVirtualStigmergy();
242  }
243  private:
248  };
249 }
250 #endif
VirtualStigmergy(const VirtualStigmergy &vs)
XmlRpcServer s
Type gets(const std::string &key)
std::vector< uint8_t > vstig_value
Definition: data_type.h:110
boost::shared_ptr< RuntimeHandle > rth_
std::vector< uint8_t > serialize_ros(T t)
Definition: serialize.h:39
static boost::shared_ptr< T > getSingleton()
Definition: singleton.h:70
void put(const std::string &key, const Type &data)
void puts(const std::string &key, const Type &data)
VirtualStigmergy & operator=(const VirtualStigmergy &vs)
boost::shared_ptr< micros_swarm::MsgQueueManager > mqm_


micros_swarm
Author(s):
autogenerated on Mon Jun 10 2019 14:02:06