template class mrpt::poses::FrameTransformerInterface
Overview
Virtual base class for interfaces to a ROS tf2 -like service capable of “publishing” and “looking-up” relative poses between two “coordinate frames”.
Use derived classes for:
wrapping real ROS tf (TO-DO in mrpt-bridge), or
using a pure MRPT standalone TF service with mrpt::poses::FrameTransformer
Frame IDs are strings. MRPT modules use the standard ROS REP 105 document regarding common names for frames:
base_link
: “the robot”odom
: Origin for odometrymap
: Origin for “the map”
Parameters:
DIM |
Can be 2 for SE(2), 2D transformations; or 3 for SE(3), 3D transformations. |
See also:
#include <mrpt/poses/FrameTransformer.h> template <int DIM> class FrameTransformerInterface { public: // construction FrameTransformerInterface(); // methods virtual FrameLookUpStatus lookupTransform( const std::string& target_frame, const std::string& source_frame, light_type& child_wrt_parent, const mrpt::system::TTimeStamp query_time = INVALID_TIMESTAMP, const double timeout_secs = .0 ) = 0; }; // direct descendants template <int DIM> class FrameTransformer;
Methods
virtual FrameLookUpStatus lookupTransform( const std::string& target_frame, const std::string& source_frame, light_type& child_wrt_parent, const mrpt::system::TTimeStamp query_time = INVALID_TIMESTAMP, const double timeout_secs = .0 ) = 0
Queries the current pose of target_frame
wrt (“as seen from”) source_frame
.
It tries to return the pose at the given timepoint, unless it is INVALID_TIMESTAMP (default), which means returning the latest know transformation.