#include <funvehiclemotionstateconverter.h>
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::APVehicle * | params_ |
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
|
inline |
|
inlineoverridevirtual |
getData returns the latest data item
Implements adore::mad::AReader< adore::fun::VehicleMotionState9d >.
|
inlineoverridevirtual |
hasData indicates whether the data has been initialized with a first data item
Implements adore::mad::AReader< adore::fun::VehicleMotionState9d >.
|
inlineoverridevirtual |
hasUpdate indicates whether the data item was updated since last getdata
Implements adore::mad::AReader< adore::fun::VehicleMotionState9d >.
|
inlineprivate |
|
inlineprivate |
|
inlineprivate |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |