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

#include <simvehicleresetconverter.h>

Collaboration diagram for adore::if_ROS::SimVehicleResetConverter:
Collaboration graph

Public Member Functions

void operator() (geometry_msgs::PoseConstPtr msg, adore::sim::ResetVehiclePose &pose)
 
geometry_msgs::Pose operator() (const adore::sim::ResetVehiclePose &pose)
 
void operator() (geometry_msgs::TwistConstPtr msg, adore::sim::ResetVehicleTwist &twist)
 
geometry_msgs::Twist operator() (const adore::sim::ResetVehicleTwist &twist)
 

Detailed Description

Convert between adore::sim::ResetVehicle(Pose/Twist) and ROS geometry_msgs::(Pose/Twist).

Member Function Documentation

◆ operator()() [1/4]

geometry_msgs::Pose adore::if_ROS::SimVehicleResetConverter::operator() ( const adore::sim::ResetVehiclePose pose)
inline

Convert adore::sim::ResetVehiclePowe to geometry_msgs::Pose

Here is the call graph for this function:

◆ operator()() [2/4]

geometry_msgs::Twist adore::if_ROS::SimVehicleResetConverter::operator() ( const adore::sim::ResetVehicleTwist twist)
inline

Convert adore::sim::ResetVehicleTwist to geometry_msgs::Twist

Here is the call graph for this function:

◆ operator()() [3/4]

void adore::if_ROS::SimVehicleResetConverter::operator() ( geometry_msgs::PoseConstPtr  msg,
adore::sim::ResetVehiclePose pose 
)
inline

Convert geometry_msgs::Pose to adore::sim::ResetVehiclePose

Here is the call graph for this function:

◆ operator()() [4/4]

void adore::if_ROS::SimVehicleResetConverter::operator() ( geometry_msgs::TwistConstPtr  msg,
adore::sim::ResetVehicleTwist twist 
)
inline

Convert geometry_msgs::Twist to adore::sim::ResetVehicleTwist

Here is the call graph for this function:

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