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

#include <funvehiclemotionstateconverter.h>

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

Public Member Functions

 MotionStateReader (ros::NodeHandle *n, const std::string odom_topic, const std::string accelerationTopic, const std::string steeringAngleTopic, int qsize)
 
virtual bool hasData () const override
 
virtual bool hasUpdate () const override
 
virtual void getData (adore::fun::VehicleMotionState9d &value) override
 
- Public Member Functions inherited from adore::mad::AReader< adore::fun::VehicleMotionState9d >
virtual std::string getDesc ()
 

Private Member Functions

void receive_odom (nav_msgs::OdometryConstPtr msg)
 
void receive_steering (std_msgs::Float32ConstPtr msg)
 
void receive_acceleration (std_msgs::Float32ConstPtr msg)
 

Private Attributes

ros::Subscriber odom_subscriber_
 
ros::Subscriber steering_subscriber_
 
ros::Subscriber acceleration_subscriber_
 
bool odom_initialized_
 
bool steering_initialized_
 
bool acceleration_initialized_
 
bool wheel_speed_available_
 
bool changed_
 
adore::fun::VehicleMotionState9d data_
 
adore::params::APVehicleparams_
 

Detailed Description

ROS specific implementation of AReader for VehicleMotionState9d. Reads nav_msgs::Odometry, std_msgs::Float32 (steering angle), std_msgs::Float32 (acceleration) and converts to adore::fun::VehicleMotionState9d

Constructor & Destructor Documentation

◆ MotionStateReader()

adore::if_ROS::MotionStateReader::MotionStateReader ( ros::NodeHandle *  n,
const std::string  odom_topic,
const std::string  accelerationTopic,
const std::string  steeringAngleTopic,
int  qsize 
)
inline
Here is the call graph for this function:

Member Function Documentation

◆ getData()

virtual void adore::if_ROS::MotionStateReader::getData ( adore::fun::VehicleMotionState9d value)
inlineoverridevirtual

getData returns the latest data item

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

◆ hasData()

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

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

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

Here is the caller graph for this function:

◆ hasUpdate()

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

hasUpdate indicates whether the data item was updated since last getdata

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

Here is the call graph for this function:

◆ receive_acceleration()

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

◆ receive_odom()

void adore::if_ROS::MotionStateReader::receive_odom ( nav_msgs::OdometryConstPtr  msg)
inlineprivate
Here is the call graph for this function:
Here is the caller graph for this function:

◆ receive_steering()

void adore::if_ROS::MotionStateReader::receive_steering ( std_msgs::Float32ConstPtr  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::MotionStateReader::acceleration_initialized_
private

◆ acceleration_subscriber_

ros::Subscriber adore::if_ROS::MotionStateReader::acceleration_subscriber_
private

◆ changed_

bool adore::if_ROS::MotionStateReader::changed_
private

◆ data_

adore::fun::VehicleMotionState9d adore::if_ROS::MotionStateReader::data_
private

◆ odom_initialized_

bool adore::if_ROS::MotionStateReader::odom_initialized_
private

◆ odom_subscriber_

ros::Subscriber adore::if_ROS::MotionStateReader::odom_subscriber_
private

◆ params_

adore::params::APVehicle* adore::if_ROS::MotionStateReader::params_
private

◆ steering_initialized_

bool adore::if_ROS::MotionStateReader::steering_initialized_
private

◆ steering_subscriber_

ros::Subscriber adore::if_ROS::MotionStateReader::steering_subscriber_
private

◆ wheel_speed_available_

bool adore::if_ROS::MotionStateReader::wheel_speed_available_
private

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