#include <trafficlightsimconverter.h>
|
void | receive_simTL (adore_if_ros_msg::TrafficLightSimulation msg) |
|
ROS specific implementation of AReader for adore::env::SimTrafficLight. Receives ROS adore_if_ros_msg::TrafficLightSimulation and creates adore::env::SimTrafficLight.
◆ TrafficLightSimReader()
adore::if_ROS::TrafficLightSimReader::TrafficLightSimReader |
( |
ros::NodeHandle * |
n, |
|
|
const std::string & |
topic_tlsim, |
|
|
int |
qsize |
|
) |
| |
|
inline |
◆ getData()
◆ hasData()
virtual bool adore::if_ROS::TrafficLightSimReader::hasData |
( |
| ) |
const |
|
inlineoverridevirtual |
◆ hasUpdate()
bool adore::if_ROS::TrafficLightSimReader::hasUpdate |
( |
| ) |
const |
|
inlineoverridevirtual |
◆ receive_simTL()
void adore::if_ROS::TrafficLightSimReader::receive_simTL |
( |
adore_if_ros_msg::TrafficLightSimulation |
msg | ) |
|
|
inlineprivate |
◆ changed_
bool adore::if_ROS::TrafficLightSimReader::changed_ |
|
private |
◆ data_
◆ simTLSubscriber_
ros::Subscriber adore::if_ROS::TrafficLightSimReader::simTLSubscriber_ |
|
private |
The documentation for this class was generated from the following file: