ADORe
ADORe is a modular open source software library and toolkit for decision making, planning, control and simulation of automated vehicles
channel.h
Go to the documentation of this file.
1 /****************************************************************************/
2 // Eclipse ADORe, Automated Driving Open Research; see https://eclipse.org/adore
3 // Copyright (C) 2017-2020 German Aerospace Center (DLR).
4 // This program and the accompanying materials
5 // are made available under the terms of the Eclipse Public License v2.0
6 // which accompanies this distribution, and is available at
7 // http://www.eclipse.org/legal/epl-v20.html
8 // SPDX-License-Identifier: EPL-2.0
9 /****************************************************************************/
16 // Channel class models probabilistic message transfer for v2x
17 #pragma once
18 #include <ros/ros.h>
19 #include <string>
20 #include <list>
21 #include <algorithm>
22 #include <adore_v2x_sim/station.h>
23 #include <adore_v2x_sim/V2XMetaSim.h>
24 #include <limits>
25 #include <random>
26 // #include <boost/random.hpp>
27 
28 namespace adore_v2x_sim
29 {
37  class Channel
38  {
39  private:
40  ros::NodeHandle n_;
42  std::list<V2XMetaSim> event_list_;
43  std::default_random_engine generator;
44  double t_agg_;
51  double c0;
52  double tx_power;
53  double rx_sensivity;
54  double fading_std;
55 
56  void update_event_list(const V2XMetaSim& meta)
57  {
58  //erase old events
59  double now = station_->getT();
60  auto it = event_list_.begin();
61  while(it!=event_list_.end())
62  {
63  if(it->time<now-t_agg_)
64  {
65  it = event_list_.erase(it);
66  }
67  else
68  {
69  it ++;
70  }
71  }
72  //push back new event
73  event_list_.push_back(meta);
74  //sort by time
75  //event_list_.sort([](const Tevent& a,const Tevent&b){return a.first<b.first;})
76  //compute metrics
78  bytes_per_second_ = 0.0;
79  for(auto it=event_list_.begin();it!=event_list_.end();it++)bytes_per_second_+=it->bytecount;
81  }
82  public:
83  Channel(ros::NodeHandle n,Station* station,unsigned int seed):station_(station),n_(n)
84  {
85  t_agg_ = 0.1;
86  msgs_per_second_ = 0.0;
87  bytes_per_second_ = 0.0;
88  cutoff_distance_ = 500.0;
89  /*
90  * Effektive antennaheigt is: heigt -1
91  * in mobil environment the min effective antenna height should be 1 m
92  * worst case assumption for SPATEM and MAPEM from RSU
93  * RSU antenna is typically higher
94  * ToDo: The stations should contain a antenna hight information
95  */
96  height_antenna_a = 2;
97  height_antenna_b = 2;
98 
99  center_frequency = 5.9 ; // [GHz] Unit !
100  c0 = 3 * std::pow(10, 8); //speed of light
101  tx_power = 23; //dBm
102  rx_sensivity = -90; //dBm from cohda data sheet should be handled with care.
103  fading_std = 3; //dB
104 
105  generator.seed(seed);
106  }
107 
108  void notify(const V2XMetaSim& meta,bool& received,double& delay)
109  {
110  const double dx = meta.location.x-station_->getX();
111  const double dy = meta.location.y-station_->getY();
112  const double dz = meta.location.z-station_->getZ();
113  double distance = std::sqrt(dx*dx+dy*dy+dz*dz);
114  double breakpoint_distance =4*(height_antenna_a-(double)1)*(height_antenna_b-(double)1)*center_frequency*std::pow(10,9)/c0;
115  double pathloss = std::numeric_limits<double>::max();
116 
117  if (distance<10)
118  // under correlation distance the modell is not valid but in this case we will not have any trouble with the distacne or power
119  {
120  pathloss = 70;
121  //placeholder with freespace loss value
122  }
123  else if (distance<breakpoint_distance)
124  {
125  pathloss = 22.7* std::log10(distance) + 27 + 20* std::log10(center_frequency) ;
126  }
127  else
128  {
129  pathloss = 40* std::log10(distance) + 7,56 -17.3*std::log10(height_antenna_a-(double)1) - 17.3*std::log10(height_antenna_b-(double)1) + 2.7 *std::log10(center_frequency);
130  }
131  std::normal_distribution<double> distribution(0,fading_std);
132  double fading = distribution(generator);
133  double pathloss_faded = pathloss+ fading;
134  double received_power = tx_power - pathloss_faded + 2* 5;
135  //5 dBi is the typical antenna gain in mobil v2x antennas 2 times for tx and rx
136  // std::cout<<"Distance: "<<distance<<" Pathloss: "<<pathloss <<" Fadind: "<<fading <<" Pathloss + Fading: "<<pathloss_faded <<std::endl;
137  if (received_power < rx_sensivity )
138  {
139  received = false;
140  return;
141  }
142  update_event_list(meta);
143  received = true;
144  }
145  };
146 }
Definition: channel.h:38
ros::NodeHandle n_
Definition: channel.h:40
std::list< V2XMetaSim > event_list_
Definition: channel.h:42
std::default_random_engine generator
Definition: channel.h:43
double t_agg_
Definition: channel.h:44
Channel(ros::NodeHandle n, Station *station, unsigned int seed)
Definition: channel.h:83
double fading_std
Definition: channel.h:54
Station * station_
Definition: channel.h:41
void update_event_list(const V2XMetaSim &meta)
Definition: channel.h:56
double height_antenna_a
Definition: channel.h:48
double center_frequency
Definition: channel.h:50
double msgs_per_second_
Definition: channel.h:45
double tx_power
Definition: channel.h:52
double c0
Definition: channel.h:51
double bytes_per_second_
Definition: channel.h:46
double height_antenna_b
Definition: channel.h:49
void notify(const V2XMetaSim &meta, bool &received, double &delay)
Definition: channel.h:108
double cutoff_distance_
Definition: channel.h:47
double rx_sensivity
Definition: channel.h:53
Definition: station.h:29
double getY() const
Definition: station.h:57
double getZ() const
Definition: station.h:58
double getT() const
Definition: station.h:59
double getX() const
Definition: station.h:56
adoreMatrix< T, N, M > max(adoreMatrix< T, N, M > a, const adoreMatrix< T, N, M > &b)
Definition: adoremath.h:686
Definition: channel.h:29