54 const std::vector<TPolygon3D>& oldPolys,
55 std::vector<TPolygonWithPlane>& newPolys);
111 bool intersect(
const TPlane& p1,
const TPlane& p2, TObject3D&
obj);
121 bool intersect(
const TPlane& p1,
const TLine3D& p2, TObject3D&
obj);
158 bool intersect(
const TLine3D& r1,
const TLine3D& r2, TObject3D&
obj);
169 bool intersect(
const TLine2D& r1,
const TLine2D& r2, TObject2D&
obj);
179 bool intersect(
const TLine2D& r1,
const TSegment2D& s2, TObject2D&
obj);
202 bool intersect(
const TSegment2D& s1,
const TSegment2D& s2, TObject2D&
obj);
214 double getAngle(
const TPlane& p1,
const TPlane& p2);
219 double getAngle(
const TPlane& p1,
const TLine3D& r2);
232 double getAngle(
const TLine3D& r1,
const TLine3D& r2);
237 double getAngle(
const TLine2D& r1,
const TLine2D& r2);
287 const TPose2D&
p,
const double (&vector)[2], TLine2D&
r);
342 TSegment3D& newSegment)
344 project3D(segment.point1, newXYpose, newSegment.point1);
345 project3D(segment.point2, newXYpose, newSegment.point2);
359 TPolygon3D& newPolygon);
363 TObject3D& newObject);
394 std::vector<T>& newObjs)
396 size_t N = objs.size();
398 for (
size_t i = 0; i < N; i++)
project3D(objs[i], newXYpose, newObjs[i]);
414 void project2D(
const TLine2D& line,
const TPose2D& newXpose, TLine2D& newLine);
417 const TPolygon2D& polygon,
const TPose2D& newXpose, TPolygon2D& newPolygon);
420 const TObject2D&
object,
const TPose2D& newXpose, TObject2D& newObject);
427 template <
class T,
class CPOSE2D>
440 template <
class T,
class CPOSE2D>
452 const std::vector<T>& objs,
const TPose2D& newXpose,
453 std::vector<T>& newObjs)
455 size_t N = objs.size();
457 for (
size_t i = 0; i < N; i++)
project2D(objs[i], newXpose, newObjs[i]);
468 bool intersect(
const TPolygon2D& p1,
const TSegment2D& s2, TObject2D&
obj);
481 inline bool intersect(
const TLine2D& r1,
const TPolygon2D& p2, TObject2D&
obj)
487 bool intersect(
const TPolygon3D& p1,
const TSegment3D& s2, TObject3D&
obj);
489 bool intersect(
const TPolygon3D& p1,
const TLine3D& r2, TObject3D&
obj);
507 inline bool intersect(
const TPlane& p1,
const TPolygon3D& p2, TObject3D&
obj)
517 const std::vector<TPolygon3D>&
v1,
const std::vector<TPolygon3D>&
v2,
518 CSparseMatrixTemplate<TObject3D>& objs);
524 const std::vector<TPolygon3D>&
v1,
const std::vector<TPolygon3D>&
v2,
525 std::vector<TObject3D>& objs);
535 template <
class T,
class U,
class O>
537 const std::vector<T>&
v1,
const std::vector<U>&
v2,
540 size_t M =
v1.size(), N =
v2.size();
544 for (
size_t i = 0; i < M; i++)
545 for (
size_t j = 0; j < M; j++)
553 template <
class T,
class U,
class O>
555 const std::vector<T>&
v1,
const std::vector<U>&
v2, std::vector<O> objs)
559 for (
typename std::vector<T>::const_iterator it1 =
v1.begin();
560 it1 !=
v1.end(); ++it1)
562 const T& elem1 = *it1;
563 for (
typename std::vector<U>::const_iterator it2 =
v2.begin();
564 it2 !=
v2.end(); ++it2)
571 bool intersect(
const TObject2D& o1,
const TObject2D& o2, TObject2D&
obj);
573 bool intersect(
const TObject3D& o1,
const TObject3D& o2, TObject3D&
obj);
581 double distance(
const TPoint2D& p1,
const TPoint2D& p2);
583 double distance(
const TPoint3D& p1,
const TPoint3D& p2);
585 double distance(
const TLine2D& r1,
const TLine2D& r2);
587 double distance(
const TLine3D& r1,
const TLine3D& r2);
601 double distance(
const TPolygon2D& p1,
const TLine2D& l2);
602 inline double distance(
const TLine2D& l1,
const TPolygon2D& p2)
607 double distance(
const TPolygon3D& p1,
const TPolygon3D& p2);
609 double distance(
const TPolygon3D& p1,
const TSegment3D& s2);
616 double distance(
const TPolygon3D& p1,
const TLine3D& l2);
623 double distance(
const TPolygon3D& po,
const TPlane& pl);
625 inline double distance(
const TPlane& pl,
const TPolygon3D& po)
637 const std::vector<TPoint2D>& poly, TPoint2D& pMin, TPoint2D& pMax);
640 const std::vector<TPoint3D>& poly, TPoint3D& pMin, TPoint3D& pMax);
711 const std::vector<TSegment3D>& segms, std::vector<TPolygon3D>& polys);
717 const std::vector<TSegment3D>& segms, std::vector<TPolygon3D>& polys,
718 std::vector<TSegment3D>& remainder);
724 const std::vector<TObject3D>& objs, std::vector<TPolygon3D>& polys);
730 const std::vector<TObject3D>& objs, std::vector<TPolygon3D>& polys,
731 std::vector<TObject3D>& remainder);
737 const std::vector<TObject3D>& objs, std::vector<TPolygon3D>& polys,
738 std::vector<TSegment3D>& remainder1, std::vector<TObject3D>& remainder2);
754 const TPolygon2D& poly, std::vector<TPolygon2D>&
components);
760 const TPolygon3D& poly, std::vector<TPolygon3D>&
components);
797 std::vector<TPolygonWithPlane> pwp;
814 template <
class T,
class U,
class V>
817 vOut[0] =
v0[1] *
v1[2] -
v0[2] *
v1[1];
818 vOut[1] =
v0[2] *
v1[0] -
v0[0] *
v1[2];
819 vOut[2] =
v0[0] *
v1[1] -
v0[1] *
v1[0];
825 const std::vector<T>&
v0,
const std::vector<T>&
v1, std::vector<T>& v_out)
830 crossProduct3D<std::vector<T>, std::vector<T>, std::vector<T>>(
834 template <
class VEC1,
class VEC2>
838 crossProduct3D<VEC1, VEC2, VEC1>(
v0,
v1, vOut);
851 template <
class VECTOR,
class MATRIX>
867 template <
class VECTOR>
885 template <
class VECTOR,
class MATRIX>
889 ASSERT_(M.rows() == 3 && M.cols() == 3);
901 template <
class VECTOR>
913 template <
class T,
class U>
923 template <
class T,
class U>
935 const double& Px,
const double& Py,
const double& x1,
const double& y1,
936 const double& x2,
const double& y2,
double& out_x,
double& out_y);
942 const double& Px,
const double& Py,
const double& x1,
const double& y1,
943 const double& x2,
const double& y2,
double& out_x,
double& out_y);
948 const double& Px,
const double& Py,
const double& x1,
const double& y1,
949 const double& x2,
const double& y2);
952 template <
typename T>
959 template <
typename T>
961 const T x1,
const T y1,
const T z1,
const T x2,
const T y2,
const T z2)
967 template <
typename T>
974 template <
typename T>
976 const T x1,
const T y1,
const T z1,
const T x2,
const T y2,
const T z2)
984 template <
typename T>
986 const double Px,
const double Py,
const double x1,
const double y1,
987 const double x2,
const double y2, T& out_x, T& out_y)
991 out_x =
static_cast<T
>(ox);
992 out_y =
static_cast<T
>(oy);
999 const double x1,
const double y1,
const double x2,
const double y2,
1000 const double x3,
const double y3,
const double x4,
const double y4,
1001 double& ix,
double& iy);
1006 const double x1,
const double y1,
const double x2,
const double y2,
1007 const double x3,
const double y3,
const double x4,
const double y4,
1008 float& ix,
float& iy);
1014 const double& px,
const double& py,
unsigned int polyEdges,
1015 const double* poly_xs,
const double* poly_ys);
1020 template <
typename T>
1022 T
x, T
y, T v1x, T v1y, T v2x, T v2y, T v3x, T v3y, T v4x, T v4y)
1026 const T
a1 = atan2(v1y -
y, v1x -
x);
1027 const T
a2 = atan2(v2y -
y, v2x -
x);
1028 const T
a3 = atan2(v3y -
y, v3x -
x);
1029 const T a4 = atan2(v4y -
y, v4x -
x);
1035 if (
sign(da1) !=
sign(da2))
return false;
1038 if (
sign(da2) !=
sign(da3))
return false;
1048 const double& px,
const double& py,
unsigned int polyEdges,
1049 const double* poly_xs,
const double* poly_ys);
1061 const double& p1_x,
const double& p1_y,
const double& p1_z,
1062 const double& p2_x,
const double& p2_y,
const double& p2_z,
1063 const double& p3_x,
const double& p3_y,
const double& p3_z,
1064 const double& p4_x,
const double& p4_y,
const double& p4_z,
double&
x,
1065 double&
y,
double&
z,
double& dist);
1077 const double& R1_x_min,
const double& R1_x_max,
const double& R1_y_min,
1078 const double& R1_y_max,
const double& R2_x_min,
const double& R2_x_max,
1079 const double& R2_y_min,
const double& R2_y_max,
const double& R2_pose_x,
1080 const double& R2_pose_y,
const double& R2_pose_phi);
void project3D(const TPoint3D &point, const mrpt::math::TPose3D &newXYpose, TPoint3D &newPoint)
Uses the given pose 3D to project a point into a new base.
void generateAxisBaseFromDirectionAndAxis(const double(&vec)[3], uint8_t coord, CMatrixDouble44 &matrix)
Creates a homogeneus matrix (4x4) such that the coordinate given (0 for x, 1 for y, 2 for z) corresponds to the provided vector.
bool RectanglesIntersection(const double &R1_x_min, const double &R1_x_max, const double &R1_y_min, const double &R1_y_max, const double &R2_x_min, const double &R2_x_max, const double &R2_y_min, const double &R2_y_max, const double &R2_pose_x, const double &R2_pose_y, const double &R2_pose_phi)
Returns whether two rotated rectangles intersect.
bool splitInConvexComponents(const TPolygon2D &poly, std::vector< TPolygon2D > &components)
Splits a 2D polygon into convex components.
void closestFromPointToLine(const double &Px, const double &Py, const double &x1, const double &y1, const double &x2, const double &y2, double &out_x, double &out_y)
Computes the closest point from a given point to a (infinite) line.
void closestFromPointToSegment(const double &Px, const double &Py, const double &x1, const double &y1, const double &x2, const double &y2, double &out_x, double &out_y)
Computes the closest point from a given point to a segment.
bool traceRay(const std::vector< TPolygonWithPlane > &vec, const mrpt::math::TPose3D &pose, double &dist)
Fast ray tracing method using polygons' properties.
bool minDistBetweenLines(const double &p1_x, const double &p1_y, const double &p1_z, const double &p2_x, const double &p2_y, const double &p2_z, const double &p3_x, const double &p3_y, const double &p3_z, const double &p4_x, const double &p4_y, const double &p4_z, double &x, double &y, double &z, double &dist)
Calculates the minimum distance between a pair of lines.
void skew_symmetric3(const VECTOR &v, MATRIX &M)
Computes the 3x3 skew symmetric matrix from a 3-vector or 3-array: .
double closestSquareDistanceFromPointToLine(const double &Px, const double &Py, const double &x1, const double &y1, const double &x2, const double &y2)
Returns the square distance from a point to a line.
bool pointIntoPolygon2D(const double &px, const double &py, unsigned int polyEdges, const double *poly_xs, const double *poly_ys)
Returns true if the 2D point (px,py) falls INTO the given polygon.
size_t getNonNullElements() const
Gets the amount of non-null elements inside the matrix.
void assemblePolygons(const std::vector< TSegment3D > &segms, std::vector< TPolygon3D > &polys)
Tries to assemble a set of segments into a set of closed polygons.
void getSegmentBisector(const TSegment2D &sgm, TLine2D &bis)
Gets the bisector of a 2D segment.
mrpt::math::TPose3D inversePose
Plane's inverse pose.
void createFromPoseAndVector(const mrpt::math::TPose3D &p, const double(&vector)[3], TLine3D &r)
Gets a 3D line corresponding to any arbitrary vector, in the base given by the pose.
Slightly heavyweight type to speed-up calculations with polygons in 3D.
bool vectorsAreParallel2D(const T &v1, const U &v2)
Returns true if two 2D vectors are parallel.
void createPlaneFromPoseXY(const mrpt::math::TPose3D &pose, TPlane &plane)
Given a pose, creates a plane orthogonal to its Z vector.
Standard type for storing any lightweight 2D type.
Standard object for storing any 3D lightweight object.
void getAsPose2D(TPose2D &outPose) const
GLenum GLenum GLuint components
void createPlaneFromPoseAndNormal(const mrpt::math::TPose3D &pose, const double(&normal)[3], TPlane &plane)
Given a pose and any vector, creates a plane orthogonal to that vector in the pose's coordinates...
bool vectorsAreParallel3D(const T &v1, const U &v2)
Returns true if two 3D vectors are parallel.
GLsizei GLsizei GLuint * obj
void getAngleBisector(const TLine2D &l1, const TLine2D &l2, TLine2D &bis)
Gets the bisector of two lines or segments (implicit constructor will be used if necessary) ...
A sparse matrix container (with cells of any type), with iterators.
void createFromPoseY(const mrpt::math::TPose3D &p, TLine3D &r)
Gets a 3D line corresponding to the Y axis in a given pose.
void crossProduct3D(const T &v0, const U &v1, V &vOut)
Computes the cross product of two 3D vectors, returning a vector normal to both.
bool conformAPlane(const std::vector< TPoint3D > &points)
Checks whether this polygon or set of points acceptably fits a plane.
GLsizei const GLfloat * points
T square(const T x)
Inline function for the square of a number.
#define ASSERT_(f)
Defines an assertion mechanism.
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: ...
CMatrixFixed< double, 3, 3 > CMatrixDouble33
bool pointIntoQuadrangle(T x, T y, T v1x, T v1y, T v2x, T v2y, T v3x, T v3y, T v4x, T v4y)
Specialized method to check whether a point (x,y) falls into a quadrangle.
This base provides a set of functions for maths stuff.
2D segment, consisting of two points.
3D segment, consisting of two points.
double distancePointToPolygon2D(const double &px, const double &py, unsigned int polyEdges, const double *poly_xs, const double *poly_ys)
Returns the closest distance of a given 2D point to a polygon, or "0" if the point is INTO the polygo...
void getRectangleBounds(const std::vector< TPoint2D > &poly, TPoint2D &pMin, TPoint2D &pMax)
Gets the rectangular bounds of a 2D polygon or set of 2D points.
void createPlaneFromPoseXZ(const mrpt::math::TPose3D &pose, TPlane &plane)
Given a pose, creates a plane orthogonal to its Y vector.
TPolygon3D poly
Actual polygon.
void setEpsilon(double nE)
Changes the value of the geometric epsilon (default = 1e-5)
3D Plane, represented by its equation
double getRegressionPlane(const std::vector< TPoint3D > &points, TPlane &plane)
Using eigenvalues, gets the best fitting plane for a set of 3D points.
TPoint2D point2
Destiny point.
TPolygon2D poly2D
Polygon, after being projected to the plane using inversePose.
double getAngle(const TPlane &p1, const TPlane &p2)
Computes the angle between two planes.
static void getPlanes(const std::vector< TPolygon3D > &oldPolys, std::vector< TPolygonWithPlane > &newPolys)
Static method for vectors.
T wrapToPi(T a)
Modifies the given angle to translate it into the ]-pi,pi] range.
TPoint2D point1
Origin point.
bool SegmentsIntersection(const double x1, const double y1, const double x2, const double y2, const double x3, const double y3, const double x4, const double y4, double &ix, double &iy)
Returns the intersection point, and if it exists, between two segments.
void clear()
Completely removes all elements, although maintaining the matrix's size.
TPolygonWithPlane()=default
Basic constructor.
void getAsPose2DForcingOrigin(const TPoint2D &origin, TPose2D &outPose) const
GLdouble GLdouble GLdouble r
double getRegressionLine(const std::vector< TPoint2D > &points, TLine2D &line)
Using eigenvalues, gets the best fitting line for a set of 2D points.
void createFromPoseX(const mrpt::math::TPose3D &p, TLine3D &r)
Gets a 3D line corresponding to the X axis in a given pose.
mrpt::math::TPose3D pose
Plane's pose.
void getPrismBounds(const std::vector< TPoint3D > &poly, TPoint3D &pMin, TPoint3D &pMax)
Gets the prism bounds of a 3D polygon or set of 3D points.
double getEpsilon()
Gets the value of the geometric epsilon (default = 1e-5)
void resize(size_t nRows, size_t nCols)
Changes the size of the matrix.
CMatrixDouble33 generateAxisBaseFromDirection(double dx, double dy, double dz)
Computes an axis base (a set of three 3D normal vectors) with the given vector being the first of the...
Lightweight 3D pose (three spatial coordinates, plus three angular coordinates).
void getAsPose3D(mrpt::math::TPose3D &outPose) const
void project2D(const TPoint2D &point, const TPose2D &newXpose, TPoint2D &newPoint)
Uses the given pose 2D to project a point into a new base.
void createFromPoseZ(const mrpt::math::TPose3D &p, TLine3D &r)
Gets a 3D line corresponding to the Z axis in a given pose.
void createPlaneFromPoseYZ(const mrpt::math::TPose3D &pose, TPlane &plane)
Given a pose, creates a plane orthogonal to its X vector.
int sign(T x)
Returns the sign of X as "1" or "-1".
bool areAligned(const std::vector< TPoint2D > &points)
Checks whether this set of points acceptably fits a 2D line.
T distanceBetweenPoints(const T x1, const T y1, const T x2, const T y2)
Returns the distance between 2 points in 2D.
GLfloat GLfloat GLfloat v2
T distanceSqrBetweenPoints(const T x1, const T y1, const T x2, const T y2)
Returns the square distance between 2 points in 2D.
TPlane plane
Plane containing the polygon.
CMatrixFixed< double, 4, 4 > CMatrixDouble44
double minimumDistanceFromPointToSegment(const double Px, const double Py, const double x1, const double y1, const double x2, const double y2, T &out_x, T &out_y)
Computes the closest point from a given point to a segment, and returns that minimum distance...
bool intersect(const TSegment3D &s1, const TSegment3D &s2, TObject3D &obj)
Gets the intersection between two 3D segments.
2D polygon, inheriting from std::vector<TPoint2D>.
3D polygon, inheriting from std::vector<TPoint3D>
double distance(const TPoint2D &p1, const TPoint2D &p2)
Gets the distance between two points in a 2D space.
void composePoint(const TPoint3D &l, TPoint3D &g) const
3D line, represented by a base point and a director vector.
2D line without bounds, represented by its equation .