12 #include <mrpt/config.h> 35 #include <Eigen/Dense> 54 m_coords[0] = m_coords[1] = m_coords[2] = 0;
59 const double x,
const double y,
const double z,
const double yaw,
77 : m_ypr_uptodate(false), m_yaw(), m_pitch(), m_roll()
87 for (
int r = 0; r < 3; r++)
88 for (
int c = 0; c < 3; c++)
m_ROT(r, c) = m(r, c);
89 for (
int r = 0; r < 3; r++)
m_coords[r] = m(r, 3);
95 for (
int r = 0; r < 3; r++)
96 for (
int c = 0; c < 3; c++)
m_ROT(r, c) = m(r, c);
97 for (
int r = 0; r < 3; r++)
m_coords[r] = m(r, 3);
132 for (
int r = 0; r < 3; r++)
133 for (
int c = 0; c < 3; c++)
out <<
m_ROT(r, c);
144 ASSERT_(HM2.rows() == 4 && HM2.isSquare());
170 in >> p[0] >> p[1] >> p[2] >> p[3] >> p[4] >> p[5] >> p[6];
176 p.quat().rotationMatrixNoResize(
m_ROT);
181 for (
int i = 0; i < 3; i++) in >>
m_coords[i];
182 for (
int r = 0; r < 3; r++)
183 for (
int c = 0; c < 3; c++) in >>
m_ROT(r, c);
208 m_coords[0] =
static_cast<double>(in[
"x"]);
209 m_coords[1] =
static_cast<double>(in[
"y"]);
210 m_coords[2] =
static_cast<double>(in[
"z"]);
225 const std::streamsize old_pre = o.precision();
226 const std::ios_base::fmtflags old_flags = o.flags();
227 o <<
"(x,y,z,yaw,pitch,roll)=(" << std::fixed << std::setprecision(4)
229 << std::setprecision(2) <<
RAD2DEG(p.
yaw()) <<
"deg," 232 o.precision(old_pre);
247 const char* fields[] = {
"R",
"t"};
248 mexplus::MxArray pose_struct(
249 mexplus::MxArray::Struct(
sizeof(fields) /
sizeof(fields[0]), fields));
252 return pose_struct.release();
266 const double x0,
const double y0,
const double z0,
const double yaw,
313 const TPoint3D& point,
double& out_range,
double& out_yaw,
314 double& out_pitch)
const 319 point.
x, point.
y, point.
z, local.
x, local.
y, local.
z);
322 out_range = local.
norm();
325 if (local.
y != 0 || local.
x != 0)
326 out_yaw = atan2(local.
y, local.
x);
332 out_pitch = -asin(local.
z / out_range);
378 double lx,
double ly,
double lz,
double& gx,
double& gy,
double& gz,
382 bool use_small_rot_approx)
const 385 if (out_jacobian_df_dpoint) out_jacobian_df_dpoint.value().get() =
m_ROT;
388 if (out_jacobian_df_dpose)
390 if (use_small_rot_approx)
393 alignas(MRPT_MAX_STATIC_ALIGN_BYTES)
const double nums[3 * 6] = {
394 1, 0, 0, -ly, lz, 0, 0, 1, 0, lx, 0, -lz, 0, 0, 1, 0, -lx, ly};
403 ::sincos(
m_yaw, &sy, &cy);
407 ::sincos(
m_roll, &sr, &cr);
409 const double cy = cos(
m_yaw);
410 const double sy = sin(
m_yaw);
411 const double cp = cos(
m_pitch);
412 const double sp = sin(
m_pitch);
413 const double cr = cos(
m_roll);
414 const double sr = sin(
m_roll);
417 alignas(MRPT_MAX_STATIC_ALIGN_BYTES)
const double nums[3 * 6] = {
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),
430 lx * cy * cp + ly * (cy * sp * sr - sy * cr) +
431 lz * (cy * sp * cr + sy * sr),
432 -lx * sy * sp + ly * (sy * cp * sr) +
434 ly * (sy * sp * cr - cy * sr) +
435 lz * (-sy * sp * sr - cy * cr),
440 -lx * cp - ly * sp * sr - lz * sp * cr,
441 ly * cp * cr - lz * cp * sr
443 out_jacobian_df_dpose.value().get().loadFromArray(nums);
452 if (out_jacobian_df_dse3)
454 alignas(MRPT_MAX_STATIC_ALIGN_BYTES)
const double nums[3 * 6] = {
455 1, 0, 0, 0, gz, -gy, 0, 1, 0, -gz, 0, gx, 0, 0, 1, gy, -gx, 0};
456 out_jacobian_df_dse3.value().get().loadFromArray(nums);
525 .maxCoeff() >= 1e-6);
539 m_ROT(2, 2) * b.z());
563 for (
int r = 0; r < 3; r++)
564 m_coords[r] =
A.m_coords[r] +
A.m_ROT(r, 0) * B_coords[0] +
565 A.m_ROT(r, 1) * B_coords[1] +
566 A.m_ROT(r, 2) * B_coords[2];
570 for (
int r = 0; r < 3; r++)
603 (fabs(
m_roll) <= tolerance ||
627 for (
int i = 0; i < 3; i++)
628 m_coords[i] = t_b_inv[i] + R_b_inv(i, 0) *
A.m_coords[0] +
629 R_b_inv(i, 1) *
A.m_coords[1] +
630 R_b_inv(i, 2) *
A.m_coords[2];
633 m_ROT = R_b_inv *
A.m_ROT;
641 const double gx,
const double gy,
const double gz,
double& lx,
double& ly,
652 if (out_jacobian_df_dpoint) out_jacobian_df_dpoint.value().get() = R_inv;
655 if (out_jacobian_df_dpose)
663 ::sincos(
m_yaw, &sy, &cy);
667 ::sincos(
m_roll, &sr, &cr);
669 const double cy = cos(
m_yaw);
670 const double sy = sin(
m_yaw);
671 const double cp = cos(
m_pitch);
672 const double sp = sin(
m_pitch);
673 const double cr = cos(
m_roll);
674 const double sr = sin(
m_roll);
677 const double m11_dy = -sy * cp;
678 const double m12_dy = cy * cp;
679 const double m13_dy = 0;
680 const double m11_dp = -cy * sp;
681 const double m12_dp = -sy * sp;
682 const double m13_dp = -cp;
683 const double m11_dr = 0;
684 const double m12_dr = 0;
685 const double m13_dr = 0;
687 const double m21_dy = (-sy * sp * sr - cy * cr);
688 const double m22_dy = (cy * sp * sr - sy * cr);
689 const double m23_dy = 0;
690 const double m21_dp = (cy * cp * sr);
691 const double m22_dp = (sy * cp * sr);
692 const double m23_dp = -sp * sr;
693 const double m21_dr = (cy * sp * cr + sy * sr);
694 const double m22_dr = (sy * sp * cr - cy * sr);
695 const double m23_dr = cp * cr;
697 const double m31_dy = (-sy * sp * cr + cy * sr);
698 const double m32_dy = (cy * sp * cr + sy * sr);
699 const double m33_dy = 0;
700 const double m31_dp = (cy * cp * cr);
701 const double m32_dp = (sy * cp * cr);
702 const double m33_dp = -sp * cr;
703 const double m31_dr = (-cy * sp * sr + sy * cr);
704 const double m32_dr = (-sy * sp * sr - cy * cr);
705 const double m33_dr = -cp * sr;
711 alignas(MRPT_MAX_STATIC_ALIGN_BYTES)
const double nums[3 * 6] = {
715 Ax * m11_dy + Ay * m12_dy + Az * m13_dy,
716 Ax * m11_dp + Ay * m12_dp + Az * m13_dp,
717 Ax * m11_dr + Ay * m12_dr + Az * m13_dr,
722 Ax * m21_dy + Ay * m22_dy + Az * m23_dy,
723 Ax * m21_dp + Ay * m22_dp + Az * m23_dp,
724 Ax * m21_dr + Ay * m22_dr + Az * m23_dr,
729 Ax * m31_dy + Ay * m32_dy + Az * m33_dy,
730 Ax * m31_dp + Ay * m32_dp + Az * m33_dp,
731 Ax * m31_dr + Ay * m32_dr + Az * m33_dr,
736 lx = t_inv[0] + R_inv(0, 0) * gx + R_inv(0, 1) * gy + R_inv(0, 2) * gz;
737 ly = t_inv[1] + R_inv(1, 0) * gx + R_inv(1, 1) * gy + R_inv(1, 2) * gz;
738 lz = t_inv[2] + R_inv(2, 0) * gx + R_inv(2, 1) * gy + R_inv(2, 2) * gz;
741 if (out_jacobian_df_dse3)
743 alignas(MRPT_MAX_STATIC_ALIGN_BYTES)
const double nums[3 * 6] = {
744 -1, 0, 0, 0, -lz, ly, 0, -1, 0, lz, 0, -lx, 0, 0, -1, -ly, lx, 0};
751 for (
int i = 0; i < 3; i++)
752 for (
int j = 0; j < 3; j++)
753 m_ROT(i, j) = std::numeric_limits<double>::quiet_NaN();
755 for (
int i = 0; i < 3; i++)
756 m_coords[i] = std::numeric_limits<double>::quiet_NaN();
772 m(0, 0), m(0, 1), m(0, 2),
DEG2RAD(m(0, 3)),
DEG2RAD(m(0, 4)),
785 for (
int i = 0; i < 3; i++) out_HM(i, 3) =
m_coords[i];
786 out_HM(3, 0) = out_HM(3, 1) = out_HM(3, 2) = 0.;
mrpt::math::TPose3D asTPose() const
mrpt::math::CQuaternionDouble & quat()
Read/Write access to the quaternion representing the 3D rotation.
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...
CPose3D getOppositeScalar() const
Return the opposite of the current pose instance by taking the negative of all its components individ...
A compile-time fixed-size numeric matrix container.
This class is a "CSerializable" wrapper for "CMatrixDynamic<double>".
#define THROW_EXCEPTION(msg)
mrpt::math::CVectorFixedDouble< 3 > m_coords
The translation vector [x,y,z] access directly or with x(), y(), z() setter/getter methods...
mrpt::math::CMatrixDouble33 m_ROT
The 3x3 rotation matrix, access with getRotationMatrix(), setRotationMatrix() (It's not safe to set t...
void setToNaN() override
Set all data fields to quiet NaN.
bool isHorizontal(const double tolerance=0) const
Return true if the 6D pose represents a Z axis almost exactly vertical (upwards or downwards)...
double roll
Roll coordinate (rotation angle over X coordinate).
#define IMPLEMENTS_SERIALIZABLE(class_name, base, NameSpace)
To be added to all CSerializable-classes implementation files.
bool m_ypr_uptodate
Whether yaw/pitch/roll members are up-to-date since the last rotation matrix update.
uint8_t serializeGetVersion() const override
Must return the current versioning number of the object.
void inverseComposePoint(const double gx, const double gy, const double gz, double &lx, double &ly, double &lz, mrpt::optional_ref< mrpt::math::CMatrixDouble33 > out_jacobian_df_dpoint=std::nullopt, mrpt::optional_ref< mrpt::math::CMatrixDouble36 > out_jacobian_df_dpose=std::nullopt, mrpt::optional_ref< mrpt::math::CMatrixDouble36 > out_jacobian_df_dse3=std::nullopt) const
Computes the 3D point L such as .
std::ostream & operator<<(std::ostream &o, const CPoint2D &p)
Dumps a point as a string (x,y)
This file implements several operations that operate element-wise on individual or pairs of container...
void rotationMatrixNoResize(MATRIXLIKE &M) const
Fill out the top-left 3x3 block of the given matrix with the rotation matrix associated to this quate...
double pitch() const
Get the PITCH angle (in radians)
double yaw() const
Get the YAW angle (in radians)
CPose3D operator+(const CPose3D &b) const
The operator is the pose compounding operator.
void rebuildRotationMatrix()
Rebuild the homog matrix from the angles.
double yaw
Yaw coordinate (rotation angle over Z axis).
std::optional< std::reference_wrapper< T > > optional_ref
Shorter name for std::optional<std::reference_wrapper<T>>
void updateYawPitchRoll() const
Updates Yaw/pitch/roll members from the m_ROT.
void inverse()
Convert this pose into its inverse, saving the result in itself.
void getAsQuaternion(mrpt::math::CQuaternionDouble &q, mrpt::optional_ref< mrpt::math::CMatrixDouble43 > out_dq_dr=std::nullopt) const
Returns the quaternion associated to the rotation of this object (NOTE: XYZ translation is ignored) ...
mrpt::math::TVector3D rotateVector(const mrpt::math::TVector3D &local) const
Rotates a vector (i.e.
Virtual base class for "schematic archives" (JSON, XML,...)
#define MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(__V)
For use in CSerializable implementations.
double distanceEuclidean6D(const CPose3D &o) const
The euclidean distance between two poses taken as two 6-length vectors (angles in radians)...
#define ASSERT_(f)
Defines an assertion mechanism.
void loadFromArray(const VECTOR &vals)
This base provides a set of functions for maths stuff.
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...
double phi() const
Get the phi angle of the 2D pose (in radians)
constexpr double DEG2RAD(const double x)
Degrees to radians.
void getInverseHomogeneousMatrix(MATRIX44 &out_HM) const
Returns the corresponding 4x4 inverse homogeneous transformation matrix for this point or pose...
auto block(int start_row, int start_col)
non-const block(): Returns an Eigen::Block reference to the block
CPose2D operator-(const CPose2D &p)
Unary - operator: return the inverse pose "-p" (Note that is NOT the same than a pose with negative x...
void addComponents(const CPose3D &p)
Scalar sum of all 6 components: This is diferent from poses composition, which is implemented as "+" ...
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...
#define IMPLEMENTS_MEXPLUS_FROM(complete_type)
void getAsQuaternion(mrpt::math::CQuaternion< double > &q, mrpt::optional_ref< mrpt::math::CMatrixFixed< double, 4, 3 >> out_dq_dr=std::nullopt) const
Returns the quaternion associated to the rotation of this object (NOTE: XYZ translation is ignored) ...
#define ASSERTMSG_(f, __ERROR_MSG)
Defines an assertion mechanism.
bool fromMatlabStringFormat(const std::string &s, mrpt::optional_ref< std::ostream > dump_errors_here=std::nullopt)
Reads a matrix from a string in Matlab-like format, for example: "[1 0 2; 0 4 -1]" The string must st...
double x() const
Common members of all points & poses classes.
void serializeFrom(mrpt::serialization::CArchive &in, uint8_t serial_version) override
Pure virtual method for reading (deserializing) from an abstract archive.
A class used to store a 3D pose as a translation (x,y,z) and a quaternion (qr,qx,qy,qz).
void asVector(vector_t &v) const
Returns a 6x1 vector with [x y z yaw pitch roll]'.
#define ASSERT_ABOVEEQ_(__A, __B)
T wrapToPi(T a)
Modifies the given angle to translate it into the ]-pi,pi] range.
double m_yaw
These variables are updated every time that the object rotation matrix is modified (construction...
size_type rows() const
Number of rows in the matrix.
A class used to store a 2D point.
A class used to store a 3D point.
size_type cols() const
Number of columns in the matrix.
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
double roll() const
Get the ROLL angle (in radians)
void fromStringRaw(const std::string &s)
Same as fromString, but without requiring the square brackets in the string.
#define SCHEMA_DESERIALIZE_DATATYPE_VERSION()
For use inside serializeFrom(CSchemeArchiveBase) methods.
struct mxArray_tag mxArray
Forward declaration for mxArray (avoid #including as much as possible to speed up compiling) ...
double pitch
Pitch coordinate (rotation angle over Y axis).
bool operator!=(const CPoint< DERIVEDCLASS, DIM > &p1, const CPoint< DERIVEDCLASS, DIM > &p2)
return_t square(const num_t x)
Inline function for the square of a number.
void operator*=(const double s)
Scalar multiplication of x,y,z,yaw,pitch & roll (angles will be wrapped to the ]-pi,pi] interval).
void getYawPitchRoll(double &yaw, double &pitch, double &roll) const
Returns the three angles (yaw, pitch, roll), in radians, from the rotation matrix.
mrpt::math::TVector3D inverseRotateVector(const mrpt::math::TVector3D &global) const
Inverse of rotateVector(), i.e.
This class is a "CSerializable" wrapper for "CMatrixFloat".
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
void fromString(const std::string &s)
Set the current object value from a string generated by 'asString' (eg: "[x y z yaw pitch roll]"...
bool operator==(const CPoint< DERIVEDCLASS, DIM > &p1, const CPoint< DERIVEDCLASS, DIM > &p2)
Virtual base class for "archives": classes abstracting I/O streams.
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...
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
mrpt::vision::TStereoCalibResults out
virtual mxArray * writeToMatlab() const
Introduces a pure virtual method responsible for writing to a mxArray Matlab object, typically a MATLAB struct whose contents are documented in each derived class.
This file implements matrix/vector text and binary serialization.
void readTo(CSerializable &obj)
constexpr double RAD2DEG(const double x)
Radians to degrees.
CPose3D()
Default constructor, with all the coordinates set to zero.
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...
Lightweight 3D pose (three spatial coordinates, plus three angular coordinates).
EIGEN_MAP asEigen()
Get as an Eigen-compatible Eigen::Map object.
void normalizeAngles()
Rebuild the internal matrix & update the yaw/pitch/roll angles within the ]-PI,PI] range (Must be cal...
void composePoint(double lx, double ly, double lz, double &gx, double &gy, double &gz, mrpt::optional_ref< mrpt::math::CMatrixDouble33 > out_jacobian_df_dpoint=std::nullopt, mrpt::optional_ref< mrpt::math::CMatrixDouble36 > out_jacobian_df_dpose=std::nullopt, mrpt::optional_ref< mrpt::math::CMatrixDouble36 > out_jacobian_df_dse3=std::nullopt, 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...
T norm() const
Point norm: |v| = sqrt(x^2+y^2+z^2)
#define SCHEMA_SERIALIZE_DATATYPE_VERSION(ser_version)
For use inside all serializeTo(CSchemeArchiveBase) methods.
A quaternion, which can represent a 3D rotation as pair , with a real part "r" and a 3D vector ...
void getRotationMatrix(mrpt::math::CMatrixDouble33 &ROT) const
Get the 3x3 rotation matrix.
Traits for SO(n), rotations in R^n space.
void getHomogeneousMatrix(mrpt::math::CMatrixDouble44 &out_HM) const
Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (t...
void rpy(T &roll, T &pitch, T &yaw) const
Return the yaw, pitch & roll angles associated to quaternion.
void serializeTo(mrpt::serialization::CArchive &out) const override
Pure virtual method for writing (serializing) to an abstract archive.
mxArray * convertToMatlab(const MATRIX &mat)
Convert vectors, arrays and matrices into Matlab vectors/matrices.