23 #include <adore_v2x_sim/V2XMetaSim.h>
100 c0 = 3 * std::pow(10, 8);
108 void notify(
const V2XMetaSim& meta,
bool& received,
double& delay)
113 double distance = std::sqrt(dx*dx+dy*dy+dz*dz);
123 else if (distance<breakpoint_distance)
125 pathloss = 22.7* std::log10(distance) + 27 + 20* std::log10(
center_frequency) ;
131 std::normal_distribution<double> distribution(0,
fading_std);
133 double pathloss_faded = pathloss+ fading;
134 double received_power =
tx_power - pathloss_faded + 2* 5;
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
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