18 #include <adore_if_ros_msg/TrafficParticipantSetSimulation.h>
27 std::list<adore::env::traffic::Participant>
data_;
32 void receive_single(adore_if_ros_msg::TrafficParticipantSimulationConstPtr msg)
38 void receive_multi(adore_if_ros_msg::TrafficParticipantSetSimulationConstPtr msg)
40 for(
auto& item:msg->data)
48 const std::string& multi_topic,
int multi_qsize)
51 n->param(
"/tcp_no_delay", no_delay,
false);
64 return data_.size()>0;
71 value =
data_.front();
Definition: trafficparticipantconverter.h:200
Definition: trafficsimulationfeed.h:25
void receive_single(adore_if_ros_msg::TrafficParticipantSimulationConstPtr msg)
receives single message and puts data element in data_queue
Definition: trafficsimulationfeed.h:32
virtual bool hasNext() const override
Definition: trafficsimulationfeed.h:62
TPSimulationConverter converter_
Definition: trafficsimulationfeed.h:28
void receive_multi(adore_if_ros_msg::TrafficParticipantSetSimulationConstPtr msg)
receives aggregates and unpacks into data_ queue
Definition: trafficsimulationfeed.h:38
virtual void getNext(adore::env::traffic::Participant &value) override
Definition: trafficsimulationfeed.h:69
std::list< adore::env::traffic::Participant > data_
Definition: trafficsimulationfeed.h:27
ros::Subscriber multi_subscriber_
Definition: trafficsimulationfeed.h:30
ros::Subscriber single_subscriber_
Definition: trafficsimulationfeed.h:29
TrafficSimulationFeed(ros::NodeHandle *n, const std::string &single_topic, int single_qsize, const std::string &multi_topic, int multi_qsize)
Definition: trafficsimulationfeed.h:47
virtual void getLatest(adore::env::traffic::Participant &value) override
Definition: trafficsimulationfeed.h:77
Definition: com_patterns.h:29
Definition: areaofeffectconverter.h:20
Struct for representing a participant in traffic.
Definition: participant.h:30