Main MRPT website > C++ reference for MRPT 1.9.9
FrameTransformer.h
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2017, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 #pragma once
10 
11 #include <mrpt/system/datetime.h>
13 //#include <mrpt/poses/CPose3DInterpolator.h>
14 #include <mrpt/poses/SE_traits.h>
15 #include <string>
16 #include <map>
17 
18 namespace mrpt
19 {
20 namespace poses
21 {
23 {
24  LKUP_GOOD = 0,
28 };
29 
30 /** Virtual base class for interfaces to a [ROS
31 * tf2](http://wiki.ros.org/tf2)-like
32 * service capable of "publishing" and "looking-up" relative poses between two
33 * "coordinate frames".
34 * Use derived classes for:
35 * - wrapping real ROS tf (TO-DO in
36 * [mrpt-bridge](http://wiki.ros.org/mrpt_bridge)), or
37 * - using a pure MRPT standalone TF service with mrpt::poses::FrameTransformer
38 *
39 * Frame IDs are strings.
40 * MRPT modules use the standard ROS [REP
41 * 105](http://www.ros.org/reps/rep-0105.html#coordinate-frames)
42 * document regarding common names for frames:
43 * - `base_link`: "the robot"
44 * - `odom`: Origin for odometry
45 * - `map`: Origin for "the map"
46 *
47 * \tparam DIM Can be 2 for SE(2), 2D transformations; or 3 for SE(3), 3D
48 * transformations.
49 * \ingroup poses_grp
50 * \sa FrameTransformer, CPose3D
51 */
52 template <int DIM>
54 {
55  public:
56  /** This will be mapped to CPose2D (DIM=2) or CPose3D (DIM=3) */
57  typedef typename SE_traits<DIM>::pose_t pose_t;
58  /** This will be mapped to mrpt::math::TPose2D (DIM=2) or
59  * mrpt::math::TPose3D (DIM=3) */
61 
64 
65  /** Publish a time-stampped transform between two frames */
66  virtual void sendTransform(
67  const std::string& parent_frame, const std::string& child_frame,
68  const pose_t& child_wrt_parent,
69  const mrpt::system::TTimeStamp& timestamp = mrpt::system::now()) = 0;
70 
71  /** Queries the current pose of `target_frame` wrt ("as seen from")
72  * `source_frame`.
73  * It tries to return the pose at the given timepoint, unless it is
74  * INVALID_TIMESTAMP (default),
75  * which means returning the latest know transformation.
76  */
78  const std::string& target_frame, const std::string& source_frame,
79  lightweight_pose_t& child_wrt_parent,
81  /** Timeout */
82  const double timeout_secs = .0) = 0;
83 
84 }; // End of class def.
85 
86 /** See docs in FrameTransformerInterface.
87 * This class is an implementation for standalone (non ROS) applications.
88 * \ingroup poses_grp
89 * \sa FrameTransformerInterface
90 */
91 template <int DIM>
93 {
94  public:
96 
99 
100  // See base docs
101  virtual void sendTransform(
102  const std::string& parent_frame, const std::string& child_frame,
103  const typename base_t::pose_t& child_wrt_parent,
104  const mrpt::system::TTimeStamp& timestamp =
105  mrpt::system::now()) override;
106  // See base docs
108  const std::string& target_frame, const std::string& source_frame,
109  typename base_t::lightweight_pose_t& child_wrt_parent,
110  const mrpt::system::TTimeStamp query_time = INVALID_TIMESTAMP,
111  const double timeout_secs = .0) override;
112 
113  /** \overload */
115  const std::string& target_frame, const std::string& source_frame,
116  typename base_t::pose_t& child_wrt_parent,
117  const mrpt::system::TTimeStamp query_time = INVALID_TIMESTAMP,
118  /** Timeout */
119  const double timeout_secs = .0)
120  {
121  typename base_t::lightweight_pose_t p;
123  target_frame, source_frame, p, query_time, timeout_secs);
124  child_wrt_parent = typename base_t::pose_t(p);
125  return ret;
126  }
127 
128  protected:
129  // double m_max_extrapolation_time; //!< for extrapolation in the past or
130  // in the future [s]
131  // double m_max_age_pose_cache; //!< Max age of stored poses [s]
132 
133  struct TF_TreeEdge
134  {
135  // TODO: CPose{2,3}DInterpolator?
138 
140  const typename base_t::pose_t& pose_,
141  const mrpt::system::TTimeStamp& timestamp_)
142  : pose(pose_), timestamp(timestamp_)
143  {
144  }
146  };
147 
148  // map: [parent] -> { [child] -> relPoseChildWRTParent }
149  typedef std::map<std::string, typename mrpt::aligned_containers<
150  std::string, TF_TreeEdge>::map_t>
153 };
154 
155 } // ns
156 } // ns
uint64_t TTimeStamp
A system independent time type, it holds the the number of 100-nanosecond intervals since January 1...
Definition: datetime.h:32
std::map< std::string, typename mrpt::aligned_containers< std::string, TF_TreeEdge >::map_t > pose_tree_t
SE_traits< DIM >::pose_t pose_t
This will be mapped to CPose2D (DIM=2) or CPose3D (DIM=3)
mrpt::system::TTimeStamp now()
A shortcut for system::getCurrentTime.
Definition: datetime.h:76
Virtual base class for interfaces to a ROS tf2-like service capable of "publishing" and "looking-up" ...
Helper types for STL containers with Eigen memory allocators.
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.
FrameTransformerInterface< DIM > base_t
virtual FrameLookUpStatus lookupTransform(const std::string &target_frame, const std::string &source_frame, typename base_t::lightweight_pose_t &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.
GLsizei const GLchar ** string
Definition: glext.h:4101
#define INVALID_TIMESTAMP
Represents an invalid timestamp, where applicable.
Definition: datetime.h:16
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 the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
A helper class for SE(2) and SE(3) geometry-related transformations, on-manifold optimization Jacobia...
Definition: SE_traits.h:29
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.
See docs in FrameTransformerInterface.
virtual 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::system::now()) override
GLfloat GLfloat p
Definition: glext.h:6305
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) ...
TF_TreeEdge(const typename base_t::pose_t &pose_, const mrpt::system::TTimeStamp &timestamp_)



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019