MRPT  2.0.2
CRobot2DPoseEstimator.h
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2020, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 #pragma once
10 
11 #include <mrpt/core/Clock.h>
12 #include <mrpt/math/TPose2D.h>
13 #include <mrpt/math/TTwist2D.h>
14 #include <mrpt/poses/poses_frwds.h>
15 #include <mutex>
16 #include <optional>
17 
18 namespace mrpt::poses
19 {
20 /** A simple filter to estimate and extrapolate the robot 2D (x,y,phi) pose from
21  *asynchronous odometry and localization/SLAM data.
22  * The implemented model is a state vector:
23  * - TPose2D (x,y,phi) + TTwist2D (vx,vy,omega)
24  * The filter can be asked for an extrapolation for some arbitrary time `t'`,
25  *and it'll do a simple linear prediction.
26  * **All methods are thread-safe**.
27  * \ingroup poses_grp poses_pdf_grp
28  */
30 {
31  public:
32  /** Default constructor */
34  /** Destructor */
35  virtual ~CRobot2DPoseEstimator();
36  /** Resets all internal state. */
37  void reset();
38 
39  /** Updates the filter with new global-coordinates localization data from a
40  * localization or SLAM source.
41  * \param tim The timestamp of the sensor readings used to evaluate
42  * localization / SLAM.
43  */
45  const mrpt::math::TPose2D& newPose, mrpt::Clock::time_point tim);
46 
47  /** Updates the filter with new odometry readings. */
49  const mrpt::math::TPose2D& newGlobalOdometry,
50  mrpt::Clock::time_point cur_tim, bool hasVelocities = false,
51  const mrpt::math::TTwist2D& newRobotVelLocal = mrpt::math::TTwist2D());
52 
53  /** Get the estimate for a given timestamp (defaults to `now()`), obtained
54  * as:
55  *
56  * last_loc (+) [ last_odo (-) odo_ref ] (+) extrapolation_from_vw
57  *
58  * \return true is the estimate can be trusted. False if the real observed
59  * data is too old or there is no valid data yet.
60  * \sa getLatestRobotPose
61  */
62  bool getCurrentEstimate(
64  mrpt::math::TTwist2D& velGlobal,
65  mrpt::Clock::time_point tim_query = mrpt::Clock::now()) const;
66 
67  /** Get the latest known robot pose, either from odometry or localization.
68  * This differs from getCurrentEstimate() in that this method does NOT
69  * extrapolate as getCurrentEstimate() does.
70  * \return false if there is not estimation yet.
71  * \sa getCurrentEstimate
72  */
73  bool getLatestRobotPose(mrpt::math::TPose2D& pose) const;
74 
75  /** \overload */
76  bool getLatestRobotPose(mrpt::poses::CPose2D& pose) const;
77 
78  struct TOptions
79  {
80  TOptions() = default;
81  /** To consider data old, in seconds */
82  double max_odometry_age{1.0};
83  /** To consider data old, in seconds */
84  double max_localiz_age{4.0};
85  };
86 
87  /** parameters of the filter. */
89 
90  /** Auxiliary static method to extrapolate the pose of a robot located at
91  * "p" with velocities (v,w) after a time delay "delta_time". */
92  static void extrapolateRobotPose(
93  const mrpt::math::TPose2D& p,
94  const mrpt::math::TTwist2D& robot_vel_local, const double delta_time,
95  mrpt::math::TPose2D& new_p);
96 
97  private:
98  std::mutex m_cs;
99 
100  std::optional<mrpt::Clock::time_point> m_last_loc_time;
101  /** Last pose as estimated by the localization/SLAM subsystem. */
103 
104  /** The interpolated odometry position for the last "m_robot_pose" (used as
105  * "coordinates base" for subsequent odo readings) */
107 
108  std::optional<mrpt::Clock::time_point> m_last_odo_time;
110  /** Robot odometry-based velocity in a local frame of reference. */
112 
113 }; // end of class
114 
115 } // namespace mrpt::poses
std::chrono::time_point< Clock > time_point
Definition: Clock.h:25
std::optional< mrpt::Clock::time_point > m_last_odo_time
mrpt::math::TPose2D m_loc_odo_ref
The interpolated odometry position for the last "m_robot_pose" (used as "coordinates base" for subseq...
double max_odometry_age
To consider data old, in seconds.
bool getLatestRobotPose(mrpt::math::TPose2D &pose) const
Get the latest known robot pose, either from odometry or localization.
A simple filter to estimate and extrapolate the robot 2D (x,y,phi) pose from asynchronous odometry an...
static time_point now() noexcept
Returns the current time using the currently selected Clock source.
Definition: Clock.cpp:94
void reset()
Resets all internal state.
2D twist: 2D velocity vector (vx,vy) + planar angular velocity (omega)
Definition: TTwist2D.h:19
mrpt::math::TPose2D m_last_loc
Last pose as estimated by the localization/SLAM subsystem.
void processUpdateNewOdometry(const mrpt::math::TPose2D &newGlobalOdometry, mrpt::Clock::time_point cur_tim, bool hasVelocities=false, const mrpt::math::TTwist2D &newRobotVelLocal=mrpt::math::TTwist2D())
Updates the filter with new odometry readings.
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
double max_localiz_age
To consider data old, in seconds.
bool getCurrentEstimate(mrpt::math::TPose2D &pose, mrpt::math::TTwist2D &velLocal, mrpt::math::TTwist2D &velGlobal, mrpt::Clock::time_point tim_query=mrpt::Clock::now()) const
Get the estimate for a given timestamp (defaults to now()), obtained as:
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
Definition: CPose2D.h:39
virtual ~CRobot2DPoseEstimator()
Destructor.
Lightweight 2D pose.
Definition: TPose2D.h:22
TOptions params
parameters of the filter.
mrpt::math::TTwist2D m_robot_vel_local
Robot odometry-based velocity in a local frame of reference.
static void extrapolateRobotPose(const mrpt::math::TPose2D &p, const mrpt::math::TTwist2D &robot_vel_local, const double delta_time, mrpt::math::TPose2D &new_p)
Auxiliary static method to extrapolate the pose of a robot located at "p" with velocities (v...
void processUpdateNewPoseLocalization(const mrpt::math::TPose2D &newPose, mrpt::Clock::time_point tim)
Updates the filter with new global-coordinates localization data from a localization or SLAM source...
std::optional< mrpt::Clock::time_point > m_last_loc_time



Page generated by Doxygen 1.8.14 for MRPT 2.0.2 Git: 9b4fd2465 Mon May 4 16:59:08 2020 +0200 at lun may 4 17:26:07 CEST 2020