MRPT  2.0.4
List of all members | Public Types | Public Member Functions
mrpt::poses::FrameTransformerInterface< DIM > Class Template Referenceabstract

Detailed Description

template<int DIM>
class mrpt::poses::FrameTransformerInterface< DIM >

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:

Template Parameters
DIMCan be 2 for SE(2), 2D transformations; or 3 for SE(3), 3D transformations.
See also
FrameTransformer, CPose3D

Definition at line 49 of file FrameTransformer.h.

#include <mrpt/poses/FrameTransformer.h>

Inheritance diagram for mrpt::poses::FrameTransformerInterface< DIM >:

Public Types

using pose_t = typename Lie::SE< DIM >::type
 This will be mapped to CPose2D (DIM=2) or CPose3D (DIM=3) More...
 
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) More...
 

Public Member Functions

 FrameTransformerInterface ()
 
virtual ~FrameTransformerInterface ()
 
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::system::now())=0
 Publish a time-stampped transform between two frames. More...
 
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. More...
 

Member Typedef Documentation

◆ light_type

template<int DIM>
using mrpt::poses::FrameTransformerInterface< DIM >::light_type = typename Lie::SE<DIM>::light_type

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

Definition at line 56 of file FrameTransformer.h.

◆ pose_t

template<int DIM>
using mrpt::poses::FrameTransformerInterface< DIM >::pose_t = typename Lie::SE<DIM>::type

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

Definition at line 53 of file FrameTransformer.h.

Constructor & Destructor Documentation

◆ FrameTransformerInterface()

template<int DIM>
FrameTransformerInterface::FrameTransformerInterface ( )
default

◆ ~FrameTransformerInterface()

template<int DIM>
FrameTransformerInterface::~FrameTransformerInterface ( )
virtualdefault

Member Function Documentation

◆ lookupTransform()

template<int DIM>
virtual FrameLookUpStatus mrpt::poses::FrameTransformerInterface< DIM >::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 
)
pure virtual

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_secsTimeout

Implemented in mrpt::poses::FrameTransformer< DIM >, and mrpt::poses::FrameTransformer< 2 >.

◆ sendTransform()

template<int DIM>
virtual void mrpt::poses::FrameTransformerInterface< DIM >::sendTransform ( const std::string &  parent_frame,
const std::string &  child_frame,
const pose_t child_wrt_parent,
const mrpt::system::TTimeStamp timestamp = mrpt::system::now() 
)
pure virtual

Publish a time-stampped transform between two frames.




Page generated by Doxygen 1.8.14 for MRPT 2.0.4 Git: 33de1d0ad Sat Jun 20 11:02:42 2020 +0200 at sáb jun 20 17:35:17 CEST 2020