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 odometrymap
: Origin for "the map"DIM | Can be 2 for SE(2), 2D transformations; or 3 for SE(3), 3D transformations. |
Definition at line 48 of file FrameTransformer.h.
#include <mrpt/poses/FrameTransformer.h>
Public Types | |
typedef SE_traits< DIM >::pose_t | pose_t |
This will be mapped to CPose2D (DIM=2) or CPose3D (DIM=3) More... | |
typedef SE_traits< DIM >::lightweight_pose_t | lightweight_pose_t |
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 ×tamp=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, lightweight_pose_t &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... | |
typedef SE_traits<DIM>::lightweight_pose_t mrpt::poses::FrameTransformerInterface< DIM >::lightweight_pose_t |
This will be mapped to mrpt::math::TPose2D (DIM=2) or mrpt::math::TPose3D (DIM=3)
Definition at line 52 of file FrameTransformer.h.
typedef SE_traits<DIM>::pose_t mrpt::poses::FrameTransformerInterface< DIM >::pose_t |
This will be mapped to CPose2D (DIM=2) or CPose3D (DIM=3)
Definition at line 51 of file FrameTransformer.h.
FrameTransformerInterface::FrameTransformerInterface | ( | ) |
Definition at line 22 of file FrameTransformer.cpp.
|
virtual |
Definition at line 26 of file FrameTransformer.cpp.
|
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.
timeout_secs | Timeout |
Implemented in mrpt::poses::FrameTransformer< DIM >, and mrpt::poses::FrameTransformer< 2 >.
|
pure virtual |
Publish a time-stampped transform between two frames.
Page generated by Doxygen 1.8.14 for MRPT 1.5.7 Git: 5902e14cc Wed Apr 24 15:04:01 2019 +0200 at lun oct 28 01:39:17 CET 2019 |