Template Class FrameTransformerInterface

Inheritance Relationships

Derived Type

Class Documentation

template<size_t DIM>
class FrameTransformerInterface

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:

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 odometry

  • map: Origin for “the map”

Template Parameters:

DIM – Can be 2 for SE(2), 2D transformations; or 3 for SE(3), 3D transformations.

Subclassed by mrpt::poses::FrameTransformer< DIM >

Public Types

using pose_t = typename Lie::SE<DIM>::type

This will be mapped to CPose2D (DIM=2) or CPose3D (DIM=3)

using light_type = typename Lie::SE<DIM>::light_type

This will be mapped to mrpt::math::TPose2D (DIM=2) or mrpt::math::TPose3D (DIM=3)

Public Functions

FrameTransformerInterface()
virtual ~FrameTransformerInterface()
FrameTransformerInterface(const FrameTransformerInterface&) = default
FrameTransformerInterface(FrameTransformerInterface&&) = default
FrameTransformerInterface &operator=(const FrameTransformerInterface&) = default
FrameTransformerInterface &operator=(FrameTransformerInterface&&) = default
virtual void sendTransform(const std::string &parent_frame, const std::string &child_frame, const pose_t &child_wrt_parent, const mrpt::system::TTimeStamp &timestamp = mrpt::Clock::now()) = 0

Publish a time-stampped transform between two frames

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.

Parameters:

timeout_secs – Timeout