Template Class FrameTransformer

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

Class Documentation

template<size_t DIM>
class FrameTransformer : public mrpt::poses::FrameTransformerInterface<DIM>

See docs in FrameTransformerInterface. This class is an implementation for standalone (non ROS) applications.

Public Types

using base_t = FrameTransformerInterface<DIM>

Public Functions

FrameTransformer()
~FrameTransformer() override
FrameTransformer(const FrameTransformer&) = default
FrameTransformer(FrameTransformer&&) = default
FrameTransformer &operator=(const FrameTransformer&) = default
FrameTransformer &operator=(FrameTransformer&&) = default
void sendTransform(const std::string &parent_frame, const std::string &child_frame, const typename base_t::pose_t &child_wrt_parent, const mrpt::system::TTimeStamp &timestamp = mrpt::Clock::now()) override
virtual FrameLookUpStatus lookupTransform(const std::string &target_frame, const std::string &source_frame, typename base_t::light_type &child_wrt_parent, const mrpt::system::TTimeStamp query_time = INVALID_TIMESTAMP, const double timeout_secs = .0) override

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

inline FrameLookUpStatus lookupTransform(const std::string &target_frame, const std::string &source_frame, typename base_t::pose_t &child_wrt_parent, const mrpt::system::TTimeStamp query_time = INVALID_TIMESTAMP, const double timeout_secs = .0)

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Parameters:

timeout_secs – Timeout

Protected Types

using pose_tree_t = std::map<std::string, std::map<std::string, TF_TreeEdge>>

Protected Attributes

pose_tree_t m_pose_edges_buffer
struct TF_TreeEdge

Public Functions

inline TF_TreeEdge(const typename base_t::pose_t &pose_, const mrpt::system::TTimeStamp &timestamp_)
TF_TreeEdge() = default

Public Members

base_t::pose_t pose
mrpt::system::TTimeStamp timestamp = {}