Go to the documentation of this file.
12 #include <mrpt/config.h>
41 #include <mrpt/otherlibs/sophus/so3.hpp>
42 #include <mrpt/otherlibs/sophus/se3.hpp>
56 m_coords[0] = m_coords[1] = m_coords[2] = 0;
61 const double x,
const double y,
const double z,
const double yaw,
79 : m_ypr_uptodate(false), m_yaw(), m_pitch(), m_roll()
89 for (
int r = 0;
r < 3;
r++)
90 for (
int c = 0;
c < 3;
c++)
m_ROT(
r,
c) = m.get_unsafe(
r,
c);
97 for (
int r = 0;
r < 3;
r++)
98 for (
int c = 0;
c < 3;
c++)
m_ROT(
r,
c) = m.get_unsafe(
r,
c);
122 p.quat().rotationMatrixNoResize(
m_ROT);
141 out <<
q[0] <<
q[1] <<
q[2] <<
q[3] <<
q[4] <<
q[5] <<
q[6];
152 ASSERT_(HM2.rows() == 4 && HM2.isSquare());
154 m_ROT = HM2.block(0, 0, 3, 3).cast<
double>();
168 m_ROT = HM.block(0, 0, 3, 3);
180 in >>
p[0] >>
p[1] >>
p[2] >>
p[3] >>
p[4] >>
p[5] >>
p[6];
187 p.quat().rotationMatrixNoResize(
m_ROT);
199 const std::streamsize old_pre = o.precision();
200 const std::ios_base::fmtflags old_flags = o.flags();
201 o <<
"(x,y,z,yaw,pitch,roll)=(" << std::fixed << std::setprecision(4)
202 <<
p.m_coords[0] <<
"," <<
p.m_coords[1] <<
"," <<
p.m_coords[2] <<
","
203 << std::setprecision(2) <<
RAD2DEG(
p.yaw()) <<
"deg,"
206 o.precision(old_pre);
221 const char* fields[] = {
"R",
"t"};
222 mexplus::MxArray pose_struct(
223 mexplus::MxArray::Struct(
sizeof(fields) /
sizeof(fields[0]), fields));
226 return pose_struct.release();
240 const double x0,
const double y0,
const double z0,
const double yaw,
262 ::sincos(
m_yaw, &sy, &cy);
266 ::sincos(
m_roll, &sr, &cr);
268 const double cy = cos(
m_yaw);
269 const double sy = sin(
m_yaw);
270 const double cp = cos(
m_pitch);
271 const double sp = sin(
m_pitch);
272 const double cr = cos(
m_roll);
273 const double sr = sin(
m_roll);
277 cy * sp * sr - sy * cr,
278 cy * sp * cr + sy * sr,
280 sy * sp * sr + cy * cr,
281 sy * sp * cr - cy * sr,
315 const TPoint3D& point,
double& out_range,
double& out_yaw,
316 double& out_pitch)
const
324 out_range =
local.norm();
334 out_pitch = -asin(
local.z / out_range);
380 double lx,
double ly,
double lz,
double& gx,
double& gy,
double& gz,
384 bool use_small_rot_approx)
const
387 if (out_jacobian_df_dpoint) *out_jacobian_df_dpoint =
m_ROT;
390 if (out_jacobian_df_dpose)
392 if (use_small_rot_approx)
396 1, 0, 0, -ly, lz, 0, 0, 1, 0, lx, 0, -lz, 0, 0, 1, 0, -lx, ly};
405 ::sincos(
m_yaw, &sy, &cy);
409 ::sincos(
m_roll, &sr, &cr);
411 const double cy = cos(
m_yaw);
412 const double sy = sin(
m_yaw);
413 const double cp = cos(
m_pitch);
414 const double sp = sin(
m_pitch);
415 const double cr = cos(
m_roll);
416 const double sr = sin(
m_roll);
421 -lx * sy * cp + ly * (-sy * sp * sr - cy * cr) +
422 lz * (-sy * sp * cr + cy * sr),
423 -lx * cy * sp + ly * (cy * cp * sr) +
425 ly * (cy * sp * cr + sy * sr) +
426 lz * (-cy * sp * sr + sy * cr),
429 lx * cy * cp + ly * (cy * sp * sr - sy * cr) +
430 lz * (cy * sp * cr + sy * sr),
431 -lx * sy * sp + ly * (sy * cp * sr) +
433 ly * (sy * sp * cr - cy * sr) +
434 lz * (-sy * sp * sr - cy * cr),
438 -lx * cp - ly * sp * sr - lz * sp * cr,
439 ly * cp * cr - lz * cp * sr
450 if (out_jacobian_df_dse3)
453 1, 0, 0, 0, gz, -gy, 0, 1, 0, -gz, 0, gx, 0, 0, 1, gy, -gx, 0};
459 #if MRPT_HAS_SSE2 && defined(MRPT_USE_SSE2)
506 b.getInverseHomogeneousMatrix(B_INV);
534 .maxCoeff() >= 1e-6);
572 for (
int r = 0;
r < 3;
r++)
574 A.
m_ROT(
r, 1) * B_coords[1] +
575 A.
m_ROT(
r, 2) * B_coords[2];
579 for (
int r = 0;
r < 3;
r++)
612 (fabs(
m_roll) <= tolerance ||
636 for (
int i = 0; i < 3; i++)
650 const double gx,
const double gy,
const double gz,
double& lx,
double& ly,
661 if (out_jacobian_df_dpoint) *out_jacobian_df_dpoint = R_inv;
664 if (out_jacobian_df_dpose)
672 ::sincos(
m_yaw, &sy, &cy);
676 ::sincos(
m_roll, &sr, &cr);
678 const double cy = cos(
m_yaw);
679 const double sy = sin(
m_yaw);
680 const double cp = cos(
m_pitch);
681 const double sp = sin(
m_pitch);
682 const double cr = cos(
m_roll);
683 const double sr = sin(
m_roll);
686 const double m11_dy = -sy * cp;
687 const double m12_dy = cy * cp;
688 const double m13_dy = 0;
689 const double m11_dp = -cy * sp;
690 const double m12_dp = -sy * sp;
691 const double m13_dp = -cp;
692 const double m11_dr = 0;
693 const double m12_dr = 0;
694 const double m13_dr = 0;
696 const double m21_dy = (-sy * sp * sr - cy * cr);
697 const double m22_dy = (cy * sp * sr - sy * cr);
698 const double m23_dy = 0;
699 const double m21_dp = (cy * cp * sr);
700 const double m22_dp = (sy * cp * sr);
701 const double m23_dp = -sp * sr;
702 const double m21_dr = (cy * sp * cr + sy * sr);
703 const double m22_dr = (sy * sp * cr - cy * sr);
704 const double m23_dr = cp * cr;
706 const double m31_dy = (-sy * sp * cr + cy * sr);
707 const double m32_dy = (cy * sp * cr + sy * sr);
708 const double m33_dy = 0;
709 const double m31_dp = (cy * cp * cr);
710 const double m32_dp = (sy * cp * cr);
711 const double m33_dp = -sp * cr;
712 const double m31_dr = (-cy * sp * sr + sy * cr);
713 const double m32_dr = (-sy * sp * sr - cy * cr);
714 const double m33_dr = -cp * sr;
724 Ax * m11_dy + Ay * m12_dy + Az * m13_dy,
725 Ax * m11_dp + Ay * m12_dp + Az * m13_dp,
726 Ax * m11_dr + Ay * m12_dr + Az * m13_dr,
731 Ax * m21_dy + Ay * m22_dy + Az * m23_dy,
732 Ax * m21_dp + Ay * m22_dp + Az * m23_dp,
733 Ax * m21_dr + Ay * m22_dr + Az * m23_dr,
738 Ax * m31_dy + Ay * m32_dy + Az * m33_dy,
739 Ax * m31_dp + Ay * m32_dp + Az * m33_dp,
740 Ax * m31_dr + Ay * m32_dr + Az * m33_dr,
745 lx = t_inv[0] + R_inv(0, 0) * gx + R_inv(0, 1) * gy + R_inv(0, 2) * gz;
746 ly = t_inv[1] + R_inv(1, 0) * gx + R_inv(1, 1) * gy + R_inv(1, 2) * gz;
747 lz = t_inv[2] + R_inv(2, 0) * gx + R_inv(2, 1) * gy + R_inv(2, 2) * gz;
750 if (out_jacobian_df_dse3)
753 -1, 0, 0, 0, -lz, ly, 0, -1, 0, lz, 0, -lx, 0, 0, -1, -ly, lx, 0};
768 bool pseudo_exponential)
770 if (pseudo_exponential)
772 auto R = Sophus::SO3<double>::exp(mu.block<3, 1>(3, 0));
780 auto R = Sophus::SE3<double>::exp(mu);
787 Sophus::SO3<double>
R(this->
m_ROT);
788 const auto&
r =
R.log();
790 for (
int i = 0; i < 3; i++) ret[i] =
r[i];
797 auto R = Sophus::SO3<double>::exp(
w);
813 template <
class VEC3,
class MAT33>
816 v[0] =
R(2, 1) -
R(1, 2);
817 v[1] =
R(0, 2) -
R(2, 0);
818 v[2] =
R(1, 0) -
R(0, 1);
821 template <
typename VEC3,
typename MAT3x3,
typename MAT3x9>
822 inline void M3x9(
const VEC3&
a,
const MAT3x3& B, MAT3x9& RES)
825 a[0], -B(0, 2), B(0, 1), B(0, 2),
a[0], -B(0, 0), -B(0, 1),
826 B(0, 0),
a[0],
a[1], -B(1, 2), B(1, 1), B(1, 2),
a[1],
827 -B(1, 0), -B(1, 1), B(1, 0),
a[1],
a[2], -B(2, 2), B(2, 1),
828 B(2, 2),
a[2], -B(2, 0), -B(2, 1), B(2, 0),
a[2]};
829 RES.loadFromArray(vals);
844 -
b *
t[1] -
c *
t[2], 2 *
b *
t[0] -
a *
t[1],
845 2 *
c *
t[0] -
a *
t[2], -
b *
t[0] + 2 *
a *
t[1],
846 -
a *
t[0] -
c *
t[2], 2 *
c *
t[1] -
b *
t[2],
847 -
c *
t[0] + 2 *
a *
t[2], -
c *
t[1] + 2 *
b *
t[2],
848 -
a *
t[0] -
b *
t[1]};
860 const double d = 0.5 * (
R(0, 0) +
R(1, 1) +
R(2, 2) - 1);
864 a[0] =
a[1] =
a[2] = 0;
869 const double theta = acos(d);
870 const double theta2 =
square(theta);
871 const double oned2 = (1 -
square(d));
872 const double sq = std::sqrt(oned2);
873 const double cot = 1. / tan(0.5 * theta);
874 const double csc2 =
square(1. / sin(0.5 * theta));
882 skewR.multiply_Ab(
t, skewR_t);
884 skewR_t *= -(d * theta - sq) / (8 * pow(sq, 3));
888 skewR2.multiply_AB(skewR, skewR);
891 skewR2.multiply_Ab(
t, skewR2_t);
893 (((theta * sq - d * theta2) * (0.5 * theta * cot - 1)) -
894 theta * sq * ((0.25 * theta * cot) + 0.125 * theta2 * csc2 - 1)) /
895 (4 * theta2 *
square(oned2));
899 B *= -0.5 * theta / (2 * sq);
901 B += -(theta * cot - 2) / (8 * oned2) *
ddeltaRt_dR(P);
924 J.insertMatrix(3, 0, M);
929 J.insertMatrix(0, 0, M);
939 const double d = 0.5 * (
R(0, 0) +
R(1, 1) +
R(2, 2) - 1);
946 Omega2.multiply_AAt(Omega);
947 Omega2 *= 1.0 / 12.0;
958 const double theta = acos(d);
959 omega *= theta / (2 * std::sqrt(1 - d * d));
964 Omega2.multiply_AAt(Omega);
966 Omega2 *= (1 - theta / (2 * std::tan(theta * 0.5))) /
square(theta);
972 J.insertMatrix(0, 9, V_inv);
978 const double d = 0.5 * (
R(0, 0) +
R(1, 1) +
R(2, 2) - 1);
983 a[0] =
a[1] =
a[2] = 0;
988 const double theta = acos(d);
989 const double d2 =
square(d);
990 const double sq = std::sqrt(1 - d2);
992 a *= (d * theta - sq) / (4 * (sq * sq * sq));
993 B.unit(3, -theta / (2 * sq));
1001 const CPose3D& D, Eigen::Matrix<double, 12, 6>& jacob)
1003 jacob.block<9, 3>(0, 0).setZero();
1004 jacob.block<3, 3>(9, 0).setIdentity();
1005 for (
int i = 0; i < 3; i++)
1007 Eigen::Block<Eigen::Matrix<double, 12, 6>, 3, 3,
false> trg_blc =
1008 jacob.block<3, 3>(3 * i, 3);
1012 Eigen::Block<Eigen::Matrix<double, 12, 6>, 3, 3,
false> trg_blc =
1013 jacob.block<3, 3>(9, 3);
1021 const CPose3D& A,
const CPose3D& D, Eigen::Matrix<double, 12, 6>& jacob)
1023 jacob.block<9, 3>(0, 0).setZero();
1025 Eigen::Matrix<double, 3, 3> aux;
1026 for (
int i = 0; i < 3; i++)
1030 jacob.block<3, 3>(3 * i, 3) = A.
m_ROT * aux;
1033 jacob.block<3, 3>(9, 3) = A.
m_ROT * aux;
1038 for (
int i = 0; i < 3; i++)
1039 for (
int j = 0; j < 3; j++)
1040 m_ROT(i, j) = std::numeric_limits<double>::quiet_NaN();
1042 for (
int i = 0; i < 3; i++)
1043 m_coords[i] = std::numeric_limits<double>::quiet_NaN();
bool m_ypr_uptodate
Whether yaw/pitch/roll members are up-to-date since the last rotation matrix update.
void skew_symmetric3_neg(const VECTOR &v, MATRIX &M)
Computes the negative version of a 3x3 skew symmetric matrix from a 3-vector or 3-array:
static void jacob_dexpeD_de(const CPose3D &D, Eigen::Matrix< double, 12, 6 > &jacob)
The Jacobian d (e^eps * D) / d eps , with eps=increment in Lie Algebra.
mrpt::math::CArrayDouble< 3 > m_rotvec
The rotation vector [vx,vy,vz].
uint8_t serializeGetVersion() const override
Must return the current versioning number of the object.
void rebuildRotationMatrix()
Rebuild the homog matrix from the angles.
void composeFrom(const CPose3D &A, const CPose3D &B)
Makes "this = A (+) B"; this method is slightly more efficient than "this= A + B;" since it avoids th...
GLdouble GLdouble GLdouble GLdouble q
double distanceEuclidean6D(const CPose3D &o) const
The euclidean distance between two poses taken as two 6-length vectors (angles in radians).
double pitch() const
Get the PITCH angle (in radians)
void addComponents(const CPose3D &p)
Scalar sum of all 6 components: This is diferent from poses composition, which is implemented as "+" ...
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction.
void sphericalCoordinates(const mrpt::math::TPoint3D &point, double &out_range, double &out_yaw, double &out_pitch) const
Computes the spherical coordinates of a 3D point as seen from the 6D pose specified by this object.
void getYawPitchRoll(double &yaw, double &pitch, double &roll) const
Returns the three angles (yaw, pitch, roll), in radians, from the rotation matrix.
void setFromValues(const double x0, const double y0, const double z0, const double yaw=0, const double pitch=0, const double roll=0)
Set the pose from a 3D position (meters) and yaw/pitch/roll angles (radians) - This method recomputes...
void homogeneousMatrixInverse(const MATRIXLIKE1 &M, MATRIXLIKE2 &out_inverse_M)
Efficiently compute the inverse of a 4x4 homogeneous matrix by only transposing the rotation 3x3 part...
void setToNaN() override
Set all data fields to quiet NaN.
void dVinvt_dR(const CPose3D &P, CMatrixFixedNumeric< double, 3, 9 > &J)
void serializeTo(mrpt::serialization::CArchive &out) const override
Pure virtual method for writing (serializing) to an abstract archive.
CMatrixFixedNumeric< double, 3, 3 > CMatrixDouble33
void getRotationMatrix(mrpt::math::CMatrixDouble33 &ROT) const
Get the 3x3 rotation matrix.
mxArray * convertToMatlab(const Eigen::EigenBase< Derived > &mat)
Convert vectors, arrays and matrices into Matlab vectors/matrices.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
GLubyte GLubyte GLubyte GLubyte w
void ln_jacob(mrpt::math::CMatrixFixedNumeric< double, 6, 12 > &J) const
Jacobian of the logarithm of the 3x4 matrix defined by this pose.
#define THROW_EXCEPTION(msg)
A class used to store a 3D pose as a translation (x,y,z) and a quaternion (qr,qx,qy,...
#define ASSERT_(f)
Defines an assertion mechanism.
A 3D pose, with a 3D translation and a rotation in 3D parameterized in rotation-vector form (equivale...
T square(const T x)
Inline function for the square of a number.
CPose2D operator-(const CPose2D &p)
Unary - operator: return the inverse pose "-p" (Note that is NOT the same than a pose with negative x...
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
double RAD2DEG(const double x)
Radians to degrees.
void getAsQuaternion(mrpt::math::CQuaternionDouble &q, mrpt::math::CMatrixFixedNumeric< double, 4, 3 > *out_dq_dr=nullptr) const
Returns the quaternion associated to the rotation of this object (NOTE: XYZ translation is ignored)
mrpt::math::CMatrixDouble33 m_ROT
The 3x3 rotation matrix, access with getRotationMatrix(), setRotationMatrix() (It's not safe to set t...
Virtual base class for "archives": classes abstracting I/O streams.
GLdouble GLdouble GLdouble r
void getAsQuaternion(mrpt::math::CQuaternion< double > &q, mrpt::math::CMatrixFixedNumeric< double, 4, 3 > *out_dq_dr=NULL) const
Returns the quaternion associated to the rotation of this object (NOTE: XYZ translation is ignored)
void loadFromArray(const T *vals)
CPose3D operator+(const CPose3D &b) const
The operator is the pose compounding operator.
T wrapToPi(T a)
Modifies the given angle to translate it into the ]-pi,pi] range.
This class is a "CSerializable" wrapper for "CMatrixFloat".
CMatrixDouble33 ddeltaRt_dR(const CPose3D &P)
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle.
double x() const
Common members of all points & poses classes.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
mrpt::math::TPose3D asTPose() const
double x
X,Y,Z coordinates.
double m_yaw
These variables are updated every time that the object rotation matrix is modified (construction,...
bool isHorizontal(const double tolerance=0) const
Return true if the 6D pose represents a Z axis almost exactly vertical (upwards or downwards),...
static CPose3D exp(const mrpt::math::CArrayNumeric< double, 6 > &vect, bool pseudo_exponential=false)
Exponentiate a Vector in the SE(3) Lie Algebra to generate a new CPose3D (static method).
double roll() const
Get the ROLL angle (in radians)
void M3x9(const VEC3 &a, const MAT3x3 &B, MAT3x9 &RES)
bool operator!=(const CPoint< DERIVEDCLASS > &p1, const CPoint< DERIVEDCLASS > &p2)
Lightweight 3D pose (three spatial coordinates, plus three angular coordinates).
CArrayNumeric is an array for numeric types supporting several mathematical operations (actually,...
void updateYawPitchRoll() const
Updates Yaw/pitch/roll members from the m_ROT
void deltaR(const MAT33 &R, VEC3 &v)
void getAsVector(mrpt::math::CVectorDouble &v) const
Returns a 1x6 vector with [x y z yaw pitch roll].
void operator*=(const double s)
Scalar multiplication of x,y,z,yaw,pitch & roll (angles will be wrapped to the ]-pi,...
#define IMPLEMENTS_SERIALIZABLE(class_name, base, NameSpace)
This must be inserted in all CSerializable classes implementation files.
A numeric matrix of compile-time fixed size.
void inverseComposeFrom(const CPose3D &A, const CPose3D &B)
Makes this method is slightly more efficient than "this= A - B;" since it avoids the temporary objec...
double pitch
Pitch coordinate (rotation angle over Y axis).
CPose3D getOppositeScalar() const
Return the opposite of the current pose instance by taking the negative of all its components individ...
#define ASSERT_ABOVEEQ_(__A, __B)
void inverse()
Convert this pose into its inverse, saving the result in itself.
A quaternion, which can represent a 3D rotation as pair , with a real part "r" and a 3D vector ,...
CMatrixFixedNumeric< double, 4, 4 > CMatrixDouble44
void composePoint(double lx, double ly, double lz, double &gx, double &gy, double &gz, mrpt::math::CMatrixFixedNumeric< double, 3, 3 > *out_jacobian_df_dpoint=nullptr, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dpose=nullptr, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dse3=nullptr, bool use_small_rot_approx=false) const
An alternative, slightly more efficient way of doing with G and L being 3D points and P this 6D pose...
static void jacob_dAexpeD_de(const CPose3D &A, const CPose3D &D, Eigen::Matrix< double, 12, 6 > &jacob)
The Jacobian d (A * e^eps * D) / d eps , with eps=increment in Lie Algebra.
double yaw
Yaw coordinate (rotation angle over Z axis).
CPose3D()
Default constructor, with all the coordinates set to zero.
double roll
Roll coordinate (rotation angle over X coordinate).
bool operator==(const CPoint< DERIVEDCLASS > &p1, const CPoint< DERIVEDCLASS > &p2)
void skew_symmetric3(const VECTOR &v, MATRIX &M)
Computes the 3x3 skew symmetric matrix from a 3-vector or 3-array:
double yaw() const
Get the YAW angle (in radians)
void normalizeAngles()
Rebuild the internal matrix & update the yaw/pitch/roll angles within the ]-PI,PI] range (Must be cal...
This base provides a set of functions for maths stuff.
#define IMPLEMENTS_MEXPLUS_FROM(complete_type)
mrpt::math::CArrayDouble< 6 > ln() const
This is an overloaded member function, provided for convenience. It differs from the above function o...
std::ostream & operator<<(std::ostream &o, const CPoint< DERIVEDCLASS > &p)
Dumps a point as a string [x,y] or [x,y,z]
void inverseComposePoint(const double gx, const double gy, const double gz, double &lx, double &ly, double &lz, mrpt::math::CMatrixFixedNumeric< double, 3, 3 > *out_jacobian_df_dpoint=nullptr, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dpose=nullptr, mrpt::math::CMatrixFixedNumeric< double, 3, 6 > *out_jacobian_df_dse3=nullptr) const
Computes the 3D point L such as .
virtual mxArray * writeToMatlab() const
Introduces a pure virtual method responsible for writing to a mxArray Matlab object,...
A class used to store a 2D point.
A class used to store a 3D point.
#define MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(__V)
For use in CSerializable implementations.
void serializeFrom(mrpt::serialization::CArchive &in, uint8_t serial_version) override
Pure virtual method for reading (deserializing) from an abstract archive.
void setRotationMatrix(const mrpt::math::CMatrixDouble33 &ROT)
Sets the 3x3 rotation matrix.
struct mxArray_tag mxArray
Forward declaration for mxArray (avoid #including as much as possible to speed up compiling)
#define MRPT_MAX_ALIGN_BYTES
static void ln_rot_jacob(const mrpt::math::CMatrixDouble33 &R, mrpt::math::CMatrixFixedNumeric< double, 3, 9 > &M)
Static function to compute the Jacobian of the SO(3) Logarithm function, evaluated at a given 3x3 rot...
@ UNINITIALIZED_QUATERNION
mrpt::math::CArrayDouble< 3 > ln_rotation() const
Take the logarithm of the 3x3 rotation matrix, generating the corresponding vector in the Lie Algebra...
GLubyte GLubyte GLubyte a
static mrpt::math::CMatrixDouble33 exp_rotation(const mrpt::math::CArrayNumeric< double, 3 > &vect)
Exponentiate a vector in the Lie algebra to generate a new SO(3) (a 3x3 rotation matrix).
mrpt::math::CArrayDouble< 3 > m_coords
The translation vector [x,y,z] access directly or with x(), y(), z() setter/getter methods.
Page generated by Doxygen 1.8.17 for MRPT 1.9.9 Git: ad3a9d8ae Tue May 1 23:10:22 2018 -0700 at miƩ 12 jul 2023 10:03:34 CEST | |