data_type.h
Go to the documentation of this file.
00001 
00023 #ifndef DATA_TYPE_H_
00024 #define DATA_TYPE_H_
00025 
00026 #include <iostream>
00027 #include <time.h>
00028 #include <math.h>
00029 #include <vector>
00030 #include <boost/archive/text_oarchive.hpp>
00031 #include <boost/archive/text_iarchive.hpp>
00032 #include <boost/serialization/string.hpp>
00033 #include <boost/serialization/vector.hpp>
00034 #include <ros/time.h>
00035 
00036 namespace micros_swarm{
00037     //Robot position in the world coordinate system
00038     struct Base{
00039         float x;
00040         float y;
00041         float z;
00042             
00043         //linear velocity
00044         float vx;
00045         float vy;
00046         float vz;
00047         
00048         int valid;  //check if the data is valid. 0(unvalid), 1(valid), -1(unknown)
00049             
00050         Base() : x(0),y(0),z(0),vx(0),vy(0),vz(0),valid(-1){}
00051         //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){}
00052         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_){}
00053     };
00054     
00055     struct NeighborBase{
00056         //Polar coordinates of the neighbor robot with respect to the local robot
00057         float distance;
00058         float azimuth;
00059         float elevation;
00060         
00061         //Cartesian coordinates of the neighbor robot with respect to the local robot
00062         float x;
00063         float y;
00064         float z;
00065             
00066         //linear velocity
00067         float vx;
00068         float vy;
00069         float vz;
00070             
00071         NeighborBase():distance(0),azimuth(0),elevation(0),x(0),y(0),z(0),vx(0),vy(0),vz(0){}
00072         NeighborBase( float distance_,float azimuth_,float elevation_,float x_,float y_,float z_,float vx_,float vy_,float vz_)
00073             :distance(distance_),azimuth(azimuth_),elevation(elevation_),x(x_),y(y_),z(z_),vx(vx_),vy(vy_),vz(vz_){}
00074     };
00075     
00076     //This data structure contains all other robots's swarm information
00077     struct NeighborSwarmTuple{
00078         std::vector<int> swarm_id_vector;
00079         //when age_ is larger than the threshold, remove the tuple of the map 
00080         int age;
00081             
00082         NeighborSwarmTuple(const std::vector<int>& swarm_id_vector_, int age_):swarm_id_vector(swarm_id_vector_), age(age_){}
00083         ~NeighborSwarmTuple(){}
00084     
00085         
00086         void addSwarmID(int swarm_id)
00087         {
00088             swarm_id_vector.push_back(swarm_id);
00089         }
00090         
00091         void removeSwarmID(int swarm_id)
00092         {
00093             swarm_id_vector.erase(std::remove(swarm_id_vector.begin(), swarm_id_vector.end(), swarm_id), swarm_id_vector.end());
00094         }
00095         
00096         bool swarmIDExist(int swarm_id)
00097         {
00098             std::vector<int>::iterator it;
00099             it = std::find(swarm_id_vector.begin(), swarm_id_vector.end(), swarm_id);
00100     
00101             if(it != swarm_id_vector.end()) {
00102                 return true;
00103             }
00104             
00105             return false; 
00106         }
00107     };
00108     
00109     struct VirtualStigmergyTuple{
00110         std::vector<uint8_t> vstig_value;
00111         int lamport_clock;
00112         time_t write_timestamp;
00113         unsigned int read_count;
00114         //the id of the robot which last change the virtual stigmergy
00115         int robot_id;
00116             
00117         VirtualStigmergyTuple(): lamport_clock(0), write_timestamp(0), read_count(0), robot_id(-1){}
00118             
00119         VirtualStigmergyTuple(const std::vector<uint8_t>& value_, int clock_, time_t time_, unsigned int count_, int id_)
00120             :vstig_value(value_), lamport_clock(clock_), write_timestamp(time_), read_count(count_), robot_id(id_){}
00121             
00122         void print()
00123         {
00124             for(int i = 0; i < vstig_value.size(); i++) {
00125                 std::cout<<vstig_value[i];
00126             }
00127             std::cout<<", "<<lamport_clock<<", "<<write_timestamp<<", "<<read_count<<", "<<robot_id<<std::endl;
00128         }
00129 
00130         double getTemperature()
00131         {
00132             double Pw, Pr;
00133             time_t t = time(NULL) - write_timestamp;
00134             Pw = pow(2,  - (t - (t % 5)) / 5);
00135             if(read_count >= 100) {
00136                 Pr = 1;
00137             }
00138             else {
00139                 Pr = read_count/100.0;
00140             }
00141 
00142             //double P = 0.5*Pw + 0.5*Pr;
00143             double P = Pw + Pr;
00144             //std::cout<<"<"<<Pw<<", "<<Pr<<">"<<std::endl;
00145             return P;
00146         }
00147     };
00148 
00149     struct BlackBoardTuple{
00150         std::vector<uint8_t> bb_value;
00151         ros::Time timestamp;
00152         //the id of the robot which last change the blackboard
00153         int robot_id;
00154 
00155         BlackBoardTuple(): timestamp(ros::Time(0,0)), robot_id(-1){}
00156 
00157         BlackBoardTuple(const std::vector<uint8_t>& value_, const ros::Time& timestamp_, int id_)
00158                 :bb_value(value_), timestamp(timestamp_), robot_id(id_){}
00159 
00160         void print()
00161         {
00162             for(int i = 0; i < bb_value.size(); i++) {
00163                 std::cout<<bb_value[i];
00164             }
00165             std::cout<<", "<<timestamp<<", "<<robot_id<<std::endl;
00166         }
00167     };
00168 
00169     struct SCDSPSODataTuple{
00170         std::vector<float> pos;
00171         float val;
00172         int robot_id;
00173         int gen;
00174         time_t timestamp;
00175 
00176         SCDSPSODataTuple():val(0), robot_id(0), gen(0), timestamp(0){}
00177 
00178         SCDSPSODataTuple(const std::string& key_, const std::vector<float> pos_, float val_, int robot_id_, int gen_, time_t timestamp_)
00179                 :pos(pos_), val(val_), robot_id(robot_id_), gen(gen_), timestamp(timestamp_){}
00180 
00181         void print()
00182         {
00183             for(int i = 0; i < pos.size(); i++) {
00184                 std::cout<<pos[i]<< " ";
00185             }
00186             std::cout<<", "<<val<<", "<<robot_id<<", "<<gen<<timestamp<<std::endl;
00187         }
00188     };
00189 };
00190 
00191 #endif


micros_swarm
Author(s):
autogenerated on Thu Jun 6 2019 18:52:14