data_type.h
Go to the documentation of this file.
1 
23 #ifndef DATA_TYPE_H_
24 #define DATA_TYPE_H_
25 
26 #include <iostream>
27 #include <time.h>
28 #include <math.h>
29 #include <vector>
30 #include <boost/archive/text_oarchive.hpp>
31 #include <boost/archive/text_iarchive.hpp>
32 #include <boost/serialization/string.hpp>
33 #include <boost/serialization/vector.hpp>
34 #include <ros/time.h>
35 
36 namespace micros_swarm{
37  //Robot position in the world coordinate system
38  struct Base{
39  float x;
40  float y;
41  float z;
42 
43  //linear velocity
44  float vx;
45  float vy;
46  float vz;
47 
48  int valid; //check if the data is valid. 0(unvalid), 1(valid), -1(unknown)
49 
50  Base() : x(0),y(0),z(0),vx(0),vy(0),vz(0),valid(-1){}
51  //Base(float x_,float y_,float z_,float vx_,float vy_,float vz_) : x(x_),y(y_),z(z_),vx(vx_),vy(vy_),vz(vz_),valid(-1){}
52  Base(float x_,float y_,float z_,float vx_,float vy_,float vz_,int valid_) : x(x_),y(y_),z(z_),vx(vx_),vy(vy_),vz(vz_),valid(valid_){}
53  };
54 
55  struct NeighborBase{
56  //Polar coordinates of the neighbor robot with respect to the local robot
57  float distance;
58  float azimuth;
59  float elevation;
60 
61  //Cartesian coordinates of the neighbor robot with respect to the local robot
62  float x;
63  float y;
64  float z;
65 
66  //linear velocity
67  float vx;
68  float vy;
69  float vz;
70 
71  NeighborBase():distance(0),azimuth(0),elevation(0),x(0),y(0),z(0),vx(0),vy(0),vz(0){}
72  NeighborBase( float distance_,float azimuth_,float elevation_,float x_,float y_,float z_,float vx_,float vy_,float vz_)
73  :distance(distance_),azimuth(azimuth_),elevation(elevation_),x(x_),y(y_),z(z_),vx(vx_),vy(vy_),vz(vz_){}
74  };
75 
76  //This data structure contains all other robots's swarm information
78  std::vector<int> swarm_id_vector;
79  //when age_ is larger than the threshold, remove the tuple of the map
80  int age;
81 
82  NeighborSwarmTuple(const std::vector<int>& swarm_id_vector_, int age_):swarm_id_vector(swarm_id_vector_), age(age_){}
84 
85 
86  void addSwarmID(int swarm_id)
87  {
88  swarm_id_vector.push_back(swarm_id);
89  }
90 
91  void removeSwarmID(int swarm_id)
92  {
93  swarm_id_vector.erase(std::remove(swarm_id_vector.begin(), swarm_id_vector.end(), swarm_id), swarm_id_vector.end());
94  }
95 
96  bool swarmIDExist(int swarm_id)
97  {
98  std::vector<int>::iterator it;
99  it = std::find(swarm_id_vector.begin(), swarm_id_vector.end(), swarm_id);
100 
101  if(it != swarm_id_vector.end()) {
102  return true;
103  }
104 
105  return false;
106  }
107  };
108 
110  std::vector<uint8_t> vstig_value;
113  unsigned int read_count;
114  //the id of the robot which last change the virtual stigmergy
115  int robot_id;
116 
117  VirtualStigmergyTuple(): lamport_clock(0), write_timestamp(0), read_count(0), robot_id(-1){}
118 
119  VirtualStigmergyTuple(const std::vector<uint8_t>& value_, int clock_, time_t time_, unsigned int count_, int id_)
120  :vstig_value(value_), lamport_clock(clock_), write_timestamp(time_), read_count(count_), robot_id(id_){}
121 
122  void print()
123  {
124  for(int i = 0; i < vstig_value.size(); i++) {
125  std::cout<<vstig_value[i];
126  }
127  std::cout<<", "<<lamport_clock<<", "<<write_timestamp<<", "<<read_count<<", "<<robot_id<<std::endl;
128  }
129 
130  double getTemperature()
131  {
132  double Pw, Pr;
133  time_t t = time(NULL) - write_timestamp;
134  Pw = pow(2, - (t - (t % 5)) / 5);
135  if(read_count >= 100) {
136  Pr = 1;
137  }
138  else {
139  Pr = read_count/100.0;
140  }
141 
142  //double P = 0.5*Pw + 0.5*Pr;
143  double P = Pw + Pr;
144  //std::cout<<"<"<<Pw<<", "<<Pr<<">"<<std::endl;
145  return P;
146  }
147  };
148 
150  std::vector<uint8_t> bb_value;
152  //the id of the robot which last change the blackboard
153  int robot_id;
154 
155  BlackBoardTuple(): timestamp(ros::Time(0,0)), robot_id(-1){}
156 
157  BlackBoardTuple(const std::vector<uint8_t>& value_, const ros::Time& timestamp_, int id_)
158  :bb_value(value_), timestamp(timestamp_), robot_id(id_){}
159 
160  void print()
161  {
162  for(int i = 0; i < bb_value.size(); i++) {
163  std::cout<<bb_value[i];
164  }
165  std::cout<<", "<<timestamp<<", "<<robot_id<<std::endl;
166  }
167  };
168 
170  std::vector<float> pos;
171  float val;
172  int robot_id;
173  int gen;
174  time_t timestamp;
175 
176  SCDSPSODataTuple():val(0), robot_id(0), gen(0), timestamp(0){}
177 
178  SCDSPSODataTuple(const std::string& key_, const std::vector<float> pos_, float val_, int robot_id_, int gen_, time_t timestamp_)
179  :pos(pos_), val(val_), robot_id(robot_id_), gen(gen_), timestamp(timestamp_){}
180 
181  void print()
182  {
183  for(int i = 0; i < pos.size(); i++) {
184  std::cout<<pos[i]<< " ";
185  }
186  std::cout<<", "<<val<<", "<<robot_id<<", "<<gen<<timestamp<<std::endl;
187  }
188  };
189 };
190 
191 #endif
std::vector< float > pos
Definition: data_type.h:170
BlackBoardTuple(const std::vector< uint8_t > &value_, const ros::Time &timestamp_, int id_)
Definition: data_type.h:157
std::vector< uint8_t > vstig_value
Definition: data_type.h:110
Base(float x_, float y_, float z_, float vx_, float vy_, float vz_, int valid_)
Definition: data_type.h:52
SCDSPSODataTuple(const std::string &key_, const std::vector< float > pos_, float val_, int robot_id_, int gen_, time_t timestamp_)
Definition: data_type.h:178
void addSwarmID(int swarm_id)
Definition: data_type.h:86
NeighborBase(float distance_, float azimuth_, float elevation_, float x_, float y_, float z_, float vx_, float vy_, float vz_)
Definition: data_type.h:72
std::vector< int > swarm_id_vector
Definition: data_type.h:78
void removeSwarmID(int swarm_id)
Definition: data_type.h:91
std::vector< uint8_t > bb_value
Definition: data_type.h:150
VirtualStigmergyTuple(const std::vector< uint8_t > &value_, int clock_, time_t time_, unsigned int count_, int id_)
Definition: data_type.h:119
NeighborSwarmTuple(const std::vector< int > &swarm_id_vector_, int age_)
Definition: data_type.h:82
bool swarmIDExist(int swarm_id)
Definition: data_type.h:96


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