#include <funvehiclemotionstateconverter.h>


Public Member Functions | |
| VehicleExtendedStateReader (ros::NodeHandle *n, const std::string gear_state_topic, const std::string accelerationTopic, const std::string accelerationActiveTopic, const std::string steeringTopic, const std::string leftIndicatorTopic, const std::string rightIndicatorTopic, const std::string checkpointClearanceTopic, int qsize) | |
| virtual bool | hasData () const override |
| virtual bool | hasUpdate () const override |
| virtual void | getData (adore::fun::VehicleExtendedState &value) override |
Public Member Functions inherited from adore::mad::AReader< adore::fun::VehicleExtendedState > | |
| virtual std::string | getDesc () |
Private Member Functions | |
| void | receive_gear (std_msgs::Int8ConstPtr msg) |
| void | receive_steering (std_msgs::BoolConstPtr msg) |
| void | receive_acceleration (std_msgs::BoolConstPtr msg) |
| void | receive_accelerationActive (std_msgs::BoolConstPtr msg) |
| void | receive_left_indicator (std_msgs::BoolConstPtr msg) |
| void | receive_right_indicator (std_msgs::BoolConstPtr msg) |
| void | receive_checkpointClearance (std_msgs::BoolConstPtr msg) |
Private Attributes | |
| ros::Subscriber | gear_subscriber_ |
| ros::Subscriber | steering_subscriber_ |
| ros::Subscriber | acceleration_subscriber_ |
| ros::Subscriber | accelerationActive_subscriber_ |
| ros::Subscriber | leftIndicator_subscriber_ |
| ros::Subscriber | rightIndicator_subscriber_ |
| ros::Subscriber | checkpointClearance_subscriber_ |
| bool | gear_initialized_ |
| bool | steering_initialized_ |
| bool | acceleration_initialized_ |
| bool | accelerationActive_initialized_ |
| bool | left_indicator_initialized_ |
| bool | right_indicator_initialized_ |
| bool | checkpointClearance_initialized_ |
| bool | changed_ |
| adore::fun::VehicleExtendedState | data_ |
ROS specific implementation of AReader for VehicleExtendedState.
|
inline |

|
inlineoverridevirtual |
getData returns the latest data item
Implements adore::mad::AReader< adore::fun::VehicleExtendedState >.
|
inlineoverridevirtual |
hasData indicates whether the data has been initialized with a first data item
Implements adore::mad::AReader< adore::fun::VehicleExtendedState >.

|
inlineoverridevirtual |
hasUpdate indicates whether the data item was updated since last getdata
Implements adore::mad::AReader< adore::fun::VehicleExtendedState >.

|
inlineprivate |


|
inlineprivate |


|
inlineprivate |


|
inlineprivate |


|
inlineprivate |


|
inlineprivate |


|
inlineprivate |


|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |