The data type which will be cross compatable with geometry_msgs This is the tf2 datatype equivilant of a MessageStamped. More...
#include <transform_datatypes.h>
Public Member Functions | |
void | setData (const T &input) |
Stamped () | |
Stamped (const T &input, const ros::Time ×tamp, const std::string &frame_id) | |
Stamped (const Stamped< T > &s) | |
Public Attributes | |
std::string | frame_id_ |
The frame_id associated this data. More... | |
ros::Time | stamp_ |
The timestamp associated with this data. More... | |
The data type which will be cross compatable with geometry_msgs This is the tf2 datatype equivilant of a MessageStamped.
Definition at line 44 of file transform_datatypes.h.
|
inline |
Default constructor
Definition at line 50 of file transform_datatypes.h.
|
inline |
Full constructor
Definition at line 53 of file transform_datatypes.h.
|
inline |
Copy Constructor
Definition at line 57 of file transform_datatypes.h.
|
inline |
Set the data element
Definition at line 63 of file transform_datatypes.h.
std::string tf2::Stamped< T >::frame_id_ |
The frame_id associated this data.
Definition at line 47 of file transform_datatypes.h.
ros::Time tf2::Stamped< T >::stamp_ |
The timestamp associated with this data.
Definition at line 46 of file transform_datatypes.h.