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

#include <funvehiclemotionstateconverter.h>

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

Public Member Functions

 MotionStateFeed (ros::NodeHandle *n, const std::string odom_topic, const std::string accelerationTopic, const std::string steeringAngleTopic, int qsize)
 
virtual bool hasNext () const override
 
virtual void getNext (adore::fun::VehicleMotionState9d &value) override
 
virtual void getLatest (adore::fun::VehicleMotionState9d &value) override
 

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_
 
double ax_
 
double delta_
 
adore::params::APVehicleparams_
 
std::list< adore::fun::VehicleMotionState9dqueue_
 

Detailed Description

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

Constructor & Destructor Documentation

◆ MotionStateFeed()

adore::if_ROS::MotionStateFeed::MotionStateFeed ( 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

◆ getLatest()

virtual void adore::if_ROS::MotionStateFeed::getLatest ( adore::fun::VehicleMotionState9d value)
inlineoverridevirtual

getLatest reads the latest data element and discards all previous

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

◆ getNext()

virtual void adore::if_ROS::MotionStateFeed::getNext ( adore::fun::VehicleMotionState9d value)
inlineoverridevirtual

getNext reads the next data element

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

◆ hasNext()

virtual bool adore::if_ROS::MotionStateFeed::hasNext ( ) const
inlineoverridevirtual

hasNext indicates whether there is more data to read

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

◆ receive_acceleration()

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

◆ receive_odom()

void adore::if_ROS::MotionStateFeed::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::MotionStateFeed::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_subscriber_

ros::Subscriber adore::if_ROS::MotionStateFeed::acceleration_subscriber_
private

◆ ax_

double adore::if_ROS::MotionStateFeed::ax_
private

◆ delta_

double adore::if_ROS::MotionStateFeed::delta_
private

◆ odom_subscriber_

ros::Subscriber adore::if_ROS::MotionStateFeed::odom_subscriber_
private

◆ params_

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

◆ queue_

std::list<adore::fun::VehicleMotionState9d> adore::if_ROS::MotionStateFeed::queue_
private

◆ steering_subscriber_

ros::Subscriber adore::if_ROS::MotionStateFeed::steering_subscriber_
private

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