32 std::map<mrpt::Clock::time_point, mrpt::poses::CPose3D> old_path;
35 for (
const auto&
p : old_path)
37 m_path[
p.first] =
p.second.asTPose();
63 using doubleDuration = std::chrono::duration<double>;
64 doubleDuration durationT =
t.time_since_epoch();
65 double td = durationT.count();
66 ts[0] = std::chrono::duration_cast<doubleDuration>(p1.first.time_since_epoch()).
count();
67 ts[1] = std::chrono::duration_cast<doubleDuration>(p2.first.time_since_epoch()).
count();
68 ts[2] = std::chrono::duration_cast<doubleDuration>(p3.first.time_since_epoch()).
count();
69 ts[3] = std::chrono::duration_cast<doubleDuration>(p4.first.time_since_epoch()).
count();
85 yaw[0] = p1.second.yaw;
86 pitch[0] = p1.second.pitch;
87 roll[0] = p1.second.roll;
88 yaw[1] = p2.second.yaw;
89 pitch[1] = p2.second.pitch;
90 roll[1] = p2.second.roll;
91 yaw[2] = p3.second.yaw;
92 pitch[2] = p3.second.pitch;
93 roll[2] = p3.second.roll;
94 yaw[3] = p4.second.yaw;
95 pitch[3] = p4.second.pitch;
96 roll[3] = p4.second.roll;
128 td, ts[1], yaw[1], ts[2], yaw[2],
true);
132 td, ts[1],
roll[1], ts[2],
roll[2],
true);
139 math::leastSquareLinearFit<double, decltype(ts), 4>(td, ts, X);
141 math::leastSquareLinearFit<double, decltype(ts), 4>(td, ts, Y);
143 math::leastSquareLinearFit<double, decltype(ts), 4>(td, ts, Z);
145 math::leastSquareLinearFit<double, decltype(ts), 4>(
148 math::leastSquareLinearFit<double, decltype(ts), 4>(
149 td, ts,
pitch,
true);
151 math::leastSquareLinearFit<double, decltype(ts), 4>(
161 math::leastSquareLinearFit<double, decltype(ts), 4>(td, ts, Z);
163 math::leastSquareLinearFit<double, decltype(ts), 4>(
166 math::leastSquareLinearFit<double, decltype(ts), 4>(
167 td, ts,
pitch,
true);
169 math::leastSquareLinearFit<double, decltype(ts), 4>(
179 math::leastSquareLinearFit<double, decltype(ts), 4>(td, ts, Z);
182 math::leastSquareLinearFit<double, decltype(ts), 4>(
183 td, ts,
pitch,
true);
185 math::leastSquareLinearFit<double, decltype(ts), 4>(
192 const double ratio = (td - ts[1]) / (ts[2] - ts[1]);
194 TPose3D(0, 0, 0, yaw[1],
pitch[1],
roll[1]),
195 TPose3D(0, 0, 0, yaw[2],
pitch[2],
roll[2]), ratio, out_interp);
208 const double ratio = (td - ts[1]) / (ts[2] - ts[1]);
210 TPose3D(0, 0, 0, yaw[1],
pitch[1],
roll[1]),
211 TPose3D(0, 0, 0, yaw[2],
pitch[2],
roll[2]), ratio, out_interp);
GLuint GLuint GLsizei count
void serializeFrom(mrpt::serialization::CArchive &in, uint8_t serial_version) override
Pure virtual method for reading (deserializing) from an abstract archive.
void slerp_ypr(const mrpt::math::TPose3D &q0, const mrpt::math::TPose3D &q1, const double t, mrpt::math::TPose3D &p)
std::chrono::time_point< Clock > time_point
#define THROW_EXCEPTION(msg)
std::pair< mrpt::Clock::time_point, pose_t > TTimePosePair
#define IMPLEMENTS_SERIALIZABLE(class_name, base, NameSpace)
This must be inserted in all CSerializable classes implementation files.
CArrayNumeric is an array for numeric types supporting several mathematical operations (actually...
TPath m_path
The sequence of poses.
typename mrpt::poses::SE_traits< DIM >::lightweight_pose_t pose_t
TPose2D or TPose3D.
#define MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(__V)
For use in CSerializable implementations.
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
Virtual base class for "archives": classes abstracting I/O streams.
void unwrap2PiSequence(VECTOR &x)
Modify a sequence of angle values such as no consecutive values have a jump larger than PI in absolut...
NUMTYPE spline(const NUMTYPE t, const VECTORLIKE &x, const VECTORLIKE &y, bool wrap2pi=false)
Interpolates the value of a function in a point "t" given 4 SORTED points where "t" is between the tw...
Lightweight 3D pose (three spatial coordinates, plus three angular coordinates).
void impl_interpolation(const TTimePosePair &p1, const TTimePosePair &p2, const TTimePosePair &p3, const TTimePosePair &p4, const TInterpolatorMethod method, const mrpt::Clock::time_point &td, pose_t &out_interp) const
This class stores a time-stamped trajectory in SE(3) (CPose3D poses).
double interpolate2points(const double x, const double x0, const double y0, const double x1, const double y1, bool wrap2pi=false)
Linear interpolation/extrapolation: evaluates at "x" the line (x0,y0)-(x1,y1).
void serializeTo(mrpt::serialization::CArchive &out) const override
Pure virtual method for writing (serializing) to an abstract archive.
TInterpolatorMethod
Type to select the interpolation method in CPoseInterpolatorBase derived classes. ...