ADORe
ADORe is a modular open source software library and toolkit for decision making, planning, control and simulation of automated vehicles
channel2station.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 // ChannelToStation class handles message hand-over between simulated channel and station v2x topic
17 
18 #pragma once
19 #include <ros/ros.h>
20 #include <string>
21 #include "channel.h"
22 
23 namespace adore_v2x_sim
24 {
28  template<typename TChannelMsg,
29  typename TChannelMsgConstPtr,
30  typename TStationMsg,
31  typename TStationMsgConstPtr>
33  {
34  private:
35  ros::Publisher to_channel_publisher_;
36  ros::Publisher to_station_publisher_;
37  ros::Subscriber from_channel_subscriber_;
38  ros::Subscriber from_station_subscriber_;
41  void station_receive(TStationMsgConstPtr msg)
42  {
43  TChannelMsg msgout;
44  msgout.data=*msg;
45  msgout.meta.location.x = station_->getX();
46  msgout.meta.location.y = station_->getY();
47  msgout.meta.location.z = station_->getZ();
48  msgout.meta.time = station_->getT();
49  msgout.meta.bytecount = 100;
50  msgout.meta.power = 22.0;
51  to_channel_publisher_.publish(msgout);
52  }
53  void channel_receive(TChannelMsgConstPtr msg)
54  {
55  bool received = false;
56  double delay = 0.0;//@TODO implement delay
57  channel_->notify(msg->meta,received,delay);
58  if(received)to_station_publisher_.publish(msg->data);
59  if(received)std::cout<<"Message received"<<std::endl;
60  else std::cout<<"Message lost"<<std::endl;
61  }
62  public:
63  ChannelToStation(ros::NodeHandle& n,
64  std::string channel_incoming_topic,
65  std::string channel_outgoing_topic,
66  std::string station_incoming_topic,
67  std::string station_outgoing_topic,
68  Station* station,
69  Channel* channel
70  ):station_(station),channel_(channel)
71  {
72  from_channel_subscriber_ = n.subscribe(channel_incoming_topic,100,&ChannelToStation::channel_receive,this);
73  from_station_subscriber_ = n.subscribe(station_outgoing_topic,100,&ChannelToStation::station_receive,this);
74  to_channel_publisher_ = n.advertise<TChannelMsg>(channel_outgoing_topic,100);
75  to_station_publisher_ = n.advertise<TStationMsg>(station_incoming_topic,100);
76  }
77  };
78 }
Definition: channel2station.h:33
Station * station_
Definition: channel2station.h:39
void station_receive(TStationMsgConstPtr msg)
Definition: channel2station.h:41
ros::Publisher to_station_publisher_
Definition: channel2station.h:36
ros::Subscriber from_station_subscriber_
Definition: channel2station.h:38
ros::Subscriber from_channel_subscriber_
Definition: channel2station.h:37
void channel_receive(TChannelMsgConstPtr msg)
Definition: channel2station.h:53
Channel * channel_
Definition: channel2station.h:40
ros::Publisher to_channel_publisher_
Definition: channel2station.h:35
ChannelToStation(ros::NodeHandle &n, std::string channel_incoming_topic, std::string channel_outgoing_topic, std::string station_incoming_topic, std::string station_outgoing_topic, Station *station, Channel *channel)
Definition: channel2station.h:63
Definition: channel.h:38
void notify(const V2XMetaSim &meta, bool &received, double &delay)
Definition: channel.h:108
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
Definition: channel.h:29