ADORe
ADORe is a modular open source software library and toolkit for decision making, planning, control and simulation of automated vehicles
adore::if_ROS::VehicleExtendedStateReader Class Reference

#include <funvehiclemotionstateconverter.h>

Inheritance diagram for adore::if_ROS::VehicleExtendedStateReader:
Inheritance graph
Collaboration diagram for adore::if_ROS::VehicleExtendedStateReader:
Collaboration graph

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_
 

Detailed Description

ROS specific implementation of AReader for VehicleExtendedState.

Constructor & Destructor Documentation

◆ VehicleExtendedStateReader()

adore::if_ROS::VehicleExtendedStateReader::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 
)
inline
Here is the call graph for this function:

Member Function Documentation

◆ getData()

virtual void adore::if_ROS::VehicleExtendedStateReader::getData ( adore::fun::VehicleExtendedState value)
inlineoverridevirtual

getData returns the latest data item

Implements adore::mad::AReader< adore::fun::VehicleExtendedState >.

◆ hasData()

virtual bool adore::if_ROS::VehicleExtendedStateReader::hasData ( ) const
inlineoverridevirtual

hasData indicates whether the data has been initialized with a first data item

Implements adore::mad::AReader< adore::fun::VehicleExtendedState >.

Here is the caller graph for this function:

◆ hasUpdate()

virtual bool adore::if_ROS::VehicleExtendedStateReader::hasUpdate ( ) const
inlineoverridevirtual

hasUpdate indicates whether the data item was updated since last getdata

Implements adore::mad::AReader< adore::fun::VehicleExtendedState >.

Here is the call graph for this function:

◆ receive_acceleration()

void adore::if_ROS::VehicleExtendedStateReader::receive_acceleration ( std_msgs::BoolConstPtr  msg)
inlineprivate
Here is the call graph for this function:
Here is the caller graph for this function:

◆ receive_accelerationActive()

void adore::if_ROS::VehicleExtendedStateReader::receive_accelerationActive ( std_msgs::BoolConstPtr  msg)
inlineprivate
Here is the call graph for this function:
Here is the caller graph for this function:

◆ receive_checkpointClearance()

void adore::if_ROS::VehicleExtendedStateReader::receive_checkpointClearance ( std_msgs::BoolConstPtr  msg)
inlineprivate
Here is the call graph for this function:
Here is the caller graph for this function:

◆ receive_gear()

void adore::if_ROS::VehicleExtendedStateReader::receive_gear ( std_msgs::Int8ConstPtr  msg)
inlineprivate
Here is the call graph for this function:
Here is the caller graph for this function:

◆ receive_left_indicator()

void adore::if_ROS::VehicleExtendedStateReader::receive_left_indicator ( std_msgs::BoolConstPtr  msg)
inlineprivate
Here is the call graph for this function:
Here is the caller graph for this function:

◆ receive_right_indicator()

void adore::if_ROS::VehicleExtendedStateReader::receive_right_indicator ( std_msgs::BoolConstPtr  msg)
inlineprivate
Here is the call graph for this function:
Here is the caller graph for this function:

◆ receive_steering()

void adore::if_ROS::VehicleExtendedStateReader::receive_steering ( std_msgs::BoolConstPtr  msg)
inlineprivate
Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ acceleration_initialized_

bool adore::if_ROS::VehicleExtendedStateReader::acceleration_initialized_
private

◆ acceleration_subscriber_

ros::Subscriber adore::if_ROS::VehicleExtendedStateReader::acceleration_subscriber_
private

◆ accelerationActive_initialized_

bool adore::if_ROS::VehicleExtendedStateReader::accelerationActive_initialized_
private

◆ accelerationActive_subscriber_

ros::Subscriber adore::if_ROS::VehicleExtendedStateReader::accelerationActive_subscriber_
private

◆ changed_

bool adore::if_ROS::VehicleExtendedStateReader::changed_
private

◆ checkpointClearance_initialized_

bool adore::if_ROS::VehicleExtendedStateReader::checkpointClearance_initialized_
private

◆ checkpointClearance_subscriber_

ros::Subscriber adore::if_ROS::VehicleExtendedStateReader::checkpointClearance_subscriber_
private

◆ data_

adore::fun::VehicleExtendedState adore::if_ROS::VehicleExtendedStateReader::data_
private

◆ gear_initialized_

bool adore::if_ROS::VehicleExtendedStateReader::gear_initialized_
private

◆ gear_subscriber_

ros::Subscriber adore::if_ROS::VehicleExtendedStateReader::gear_subscriber_
private

◆ left_indicator_initialized_

bool adore::if_ROS::VehicleExtendedStateReader::left_indicator_initialized_
private

◆ leftIndicator_subscriber_

ros::Subscriber adore::if_ROS::VehicleExtendedStateReader::leftIndicator_subscriber_
private

◆ right_indicator_initialized_

bool adore::if_ROS::VehicleExtendedStateReader::right_indicator_initialized_
private

◆ rightIndicator_subscriber_

ros::Subscriber adore::if_ROS::VehicleExtendedStateReader::rightIndicator_subscriber_
private

◆ steering_initialized_

bool adore::if_ROS::VehicleExtendedStateReader::steering_initialized_
private

◆ steering_subscriber_

ros::Subscriber adore::if_ROS::VehicleExtendedStateReader::steering_subscriber_
private

The documentation for this class was generated from the following file: