36 #include <visp3/core/vpCPUFeatures.h>
37 #include <visp3/mbt/vpMbtFaceDepthDense.h>
40 #include <pcl/common/point_tests.h>
43 #if defined __SSE2__ || defined _M_X64 || (defined _M_IX86_FP && _M_IX86_FP >= 2)
44 #include <emmintrin.h>
45 #define VISP_HAVE_SSE2 1
49 #if !defined(__FMA__) && defined(__AVX2__)
53 #if defined _WIN32 && defined(_M_ARM64)
54 #define _ARM64_DISTINCT_NEON_TYPES
57 #define VISP_HAVE_NEON 1
58 #elif (defined(__ARM_NEON__) || defined (__ARM_NEON)) && defined(__aarch64__)
60 #define VISP_HAVE_NEON 1
63 #define USE_SIMD_CODE 1
65 #if VISP_HAVE_SSE2 && USE_SIMD_CODE
71 #if VISP_HAVE_NEON && USE_SIMD_CODE
77 #if (VISP_HAVE_OPENCV_VERSION >= 0x040101 || (VISP_HAVE_OPENCV_VERSION < 0x040000 && VISP_HAVE_OPENCV_VERSION >= 0x030407)) && USE_SIMD_CODE
78 #define USE_OPENCV_HAL 1
79 #include <opencv2/core/simd_intrinsics.hpp>
80 #include <opencv2/core/hal/intrin.hpp>
83 #if !USE_OPENCV_HAL && (USE_SSE || USE_NEON)
84 #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
91 inline void v_load_deinterleave(
const uint64_t *ptr, __m128i& a, __m128i& b, __m128i& c)
93 __m128i t0 = _mm_loadu_si128((
const __m128i*)ptr);
94 __m128i t1 = _mm_loadu_si128((
const __m128i*)(ptr + 2));
95 __m128i t2 = _mm_loadu_si128((
const __m128i*)(ptr + 4));
97 t1 = _mm_shuffle_epi32(t1, 0x4e);
99 a = _mm_unpacklo_epi64(t0, t1);
100 b = _mm_unpacklo_epi64(_mm_unpackhi_epi64(t0, t0), t2);
101 c = _mm_unpackhi_epi64(t1, t2);
104 inline void v_load_deinterleave(
const double* ptr, __m128d& a0, __m128d& b0, __m128d& c0)
107 v_load_deinterleave((
const uint64_t*)ptr, a1, b1, c1);
108 a0 = _mm_castsi128_pd(a1);
109 b0 = _mm_castsi128_pd(b1);
110 c0 = _mm_castsi128_pd(c1);
113 inline __m128d v_combine_low(
const __m128d& a,
const __m128d& b)
115 __m128i a1 = _mm_castpd_si128(a), b1 = _mm_castpd_si128(b);
116 return _mm_castsi128_pd(_mm_unpacklo_epi64(a1, b1));
119 inline __m128d v_combine_high(
const __m128d& a,
const __m128d& b)
121 __m128i a1 = _mm_castpd_si128(a), b1 = _mm_castpd_si128(b);
122 return _mm_castsi128_pd(_mm_unpackhi_epi64(a1, b1));
125 inline __m128d v_fma(
const __m128d& a,
const __m128d& b,
const __m128d& c)
128 return _mm_fmadd_pd(a, b, c);
130 return _mm_add_pd(_mm_mul_pd(a, b), c);
134 inline void v_load_deinterleave(
const double* ptr, float64x2_t& a0, float64x2_t& b0, float64x2_t& c0)
136 float64x2x3_t v = vld3q_f64(ptr);
142 inline float64x2_t v_combine_low(
const float64x2_t& a,
const float64x2_t& b)
144 return vcombine_f64(vget_low_f64(a), vget_low_f64(b));
147 inline float64x2_t v_combine_high(
const float64x2_t& a,
const float64x2_t& b)
149 return vcombine_f64(vget_high_f64(a), vget_high_f64(b));
152 inline float64x2_t v_fma(
const float64x2_t& a,
const float64x2_t& b,
const float64x2_t& c)
154 return vfmaq_f64(c, a, b);
161 : m_cam(), m_clippingFlag(
vpPolygon3D::NO_CLIPPING), m_distFarClip(100), m_distNearClip(0.001), m_hiddenFace(NULL),
162 m_planeObject(), m_polygon(NULL), m_useScanLine(false),
163 m_depthDenseFilteringMethod(DEPTH_OCCUPANCY_RATIO_FILTERING), m_depthDenseFilteringMaxDist(3.0),
164 m_depthDenseFilteringMinDist(0.8), m_depthDenseFilteringOccupancyRatio(0.3), m_isTrackedDepthDenseFace(true),
165 m_isVisible(false), m_listOfFaceLines(), m_planeCamera(), m_pointCloudFace(), m_polygonLines()
191 vpUniRand &rand_gen,
int polygon, std::string name)
194 PolygonLine polygon_line;
197 polygon_line.m_poly.setNbPoint(2);
198 polygon_line.m_poly.addPoint(0, P1);
199 polygon_line.m_poly.addPoint(1, P2);
205 polygon_line.m_p1 = &polygon_line.m_poly.p[0];
206 polygon_line.m_p2 = &polygon_line.m_poly.p[1];
211 bool already_here =
false;
252 const pcl::PointCloud<pcl::PointXYZ>::ConstPtr &point_cloud,
253 unsigned int stepX,
unsigned int stepY
254 #
if DEBUG_DISPLAY_DEPTH_DENSE
257 std::vector<std::vector<vpImagePoint> > &roiPts_vec
262 unsigned int width = point_cloud->width, height = point_cloud->height;
265 if (point_cloud->width == 0 || point_cloud->height == 0)
268 std::vector<vpImagePoint> roiPts;
269 double distanceToFace;
271 #
if DEBUG_DISPLAY_DEPTH_DENSE
278 if (roiPts.size() <= 2) {
280 std::cerr <<
"Error: roiPts.size() <= 2 in computeDesiredFeatures" << std::endl;
293 unsigned int top = (
unsigned int)std::max(0.0, bb.
getTop());
294 unsigned int bottom = (
unsigned int)std::min((
double)height, std::max(0.0, bb.
getBottom()));
295 unsigned int left = (
unsigned int)std::max(0.0, bb.
getLeft());
296 unsigned int right = (
unsigned int)std::min((
double)width, std::max(0.0, bb.
getRight()));
309 int totalTheoreticalPoints = 0, totalPoints = 0;
310 for (
unsigned int i = top; i < bottom; i += stepY) {
311 for (
unsigned int j = left; j < right; j += stepX) {
312 if ((
m_useScanLine ? (i < m_hiddenFace->getMbScanLineRenderer().getPrimitiveIDs().getHeight() &&
313 j < m_hiddenFace->getMbScanLineRenderer().getPrimitiveIDs().getWidth() &&
316 totalTheoreticalPoints++;
318 if (
vpMeTracker::inMask(mask, i, j) && pcl::isFinite((*point_cloud)(j, i)) && (*point_cloud)(j, i).z > 0) {
325 #if DEBUG_DISPLAY_DEPTH_DENSE
326 debugImage[i][j] = 255;
343 unsigned int height,
const std::vector<vpColVector> &point_cloud,
344 unsigned int stepX,
unsigned int stepY
345 #
if DEBUG_DISPLAY_DEPTH_DENSE
348 std::vector<std::vector<vpImagePoint> > &roiPts_vec
355 if (width == 0 || height == 0)
358 std::vector<vpImagePoint> roiPts;
359 double distanceToFace;
361 #
if DEBUG_DISPLAY_DEPTH_DENSE
368 if (roiPts.size() <= 2) {
370 std::cerr <<
"Error: roiPts.size() <= 2 in computeDesiredFeatures" << std::endl;
383 unsigned int top = (
unsigned int)std::max(0.0, bb.
getTop());
384 unsigned int bottom = (
unsigned int)std::min((
double)height, std::max(0.0, bb.
getBottom()));
385 unsigned int left = (
unsigned int)std::max(0.0, bb.
getLeft());
386 unsigned int right = (
unsigned int)std::min((
double)width, std::max(0.0, bb.
getRight()));
395 int totalTheoreticalPoints = 0, totalPoints = 0;
396 for (
unsigned int i = top; i < bottom; i += stepY) {
397 for (
unsigned int j = left; j < right; j += stepX) {
398 if ((
m_useScanLine ? (i < m_hiddenFace->getMbScanLineRenderer().getPrimitiveIDs().getHeight() &&
399 j < m_hiddenFace->getMbScanLineRenderer().getPrimitiveIDs().getWidth() &&
402 totalTheoreticalPoints++;
411 #if DEBUG_DISPLAY_DEPTH_DENSE
412 debugImage[i][j] = 255;
436 bool isvisible =
false;
440 int index = *itindex;
487 #if !USE_SSE && !USE_NEON && !USE_OPENCV_HAL
492 #if USE_SSE || USE_NEON|| USE_OPENCV_HAL
496 double *ptr_L = L.data;
497 double *ptr_error = error.
data;
500 const cv::v_float64x2 vnx = cv::v_setall_f64(nx);
501 const cv::v_float64x2 vny = cv::v_setall_f64(ny);
502 const cv::v_float64x2 vnz = cv::v_setall_f64(nz);
503 const cv::v_float64x2 vd = cv::v_setall_f64(D);
505 const __m128d vnx = _mm_set1_pd(nx);
506 const __m128d vny = _mm_set1_pd(ny);
507 const __m128d vnz = _mm_set1_pd(nz);
508 const __m128d vd = _mm_set1_pd(D);
510 const float64x2_t vnx = vdupq_n_f64(nx);
511 const float64x2_t vny = vdupq_n_f64(ny);
512 const float64x2_t vnz = vdupq_n_f64(nz);
513 const float64x2_t vd = vdupq_n_f64(D);
516 for (; cpt <=
m_pointCloudFace.size() - 6; cpt += 6, ptr_point_cloud += 6) {
518 cv::v_float64x2 vx, vy, vz;
519 cv::v_load_deinterleave(ptr_point_cloud, vx, vy, vz);
521 cv::v_float64x2 va1 = vnz*vy - vny*vz;
522 cv::v_float64x2 va2 = vnx*vz - vnz*vx;
523 cv::v_float64x2 va3 = vny*vx - vnx*vy;
525 cv::v_float64x2 vnxy = cv::v_combine_low(vnx, vny);
526 cv::v_store(ptr_L, vnxy);
528 vnxy = cv::v_combine_low(vnz, va1);
529 cv::v_store(ptr_L, vnxy);
531 vnxy = cv::v_combine_low(va2, va3);
532 cv::v_store(ptr_L, vnxy);
535 vnxy = cv::v_combine_high(vnx, vny);
536 cv::v_store(ptr_L, vnxy);
538 vnxy = cv::v_combine_high(vnz, va1);
539 cv::v_store(ptr_L, vnxy);
541 vnxy = cv::v_combine_high(va2, va3);
542 cv::v_store(ptr_L, vnxy);
545 cv::v_float64x2 verr = vd + cv::v_muladd(vnx, vx, cv::v_muladd(vny, vy, vnz*vz));
546 cv::v_store(ptr_error, verr);
550 v_load_deinterleave(ptr_point_cloud, vx, vy, vz);
552 __m128d va1 = _mm_sub_pd(_mm_mul_pd(vnz, vy), _mm_mul_pd(vny, vz));
553 __m128d va2 = _mm_sub_pd(_mm_mul_pd(vnx, vz), _mm_mul_pd(vnz, vx));
554 __m128d va3 = _mm_sub_pd(_mm_mul_pd(vny, vx), _mm_mul_pd(vnx, vy));
556 __m128d vnxy = v_combine_low(vnx, vny);
557 _mm_storeu_pd(ptr_L, vnxy);
559 vnxy = v_combine_low(vnz, va1);
560 _mm_storeu_pd(ptr_L, vnxy);
562 vnxy = v_combine_low(va2, va3);
563 _mm_storeu_pd(ptr_L, vnxy);
566 vnxy = v_combine_high(vnx, vny);
567 _mm_storeu_pd(ptr_L, vnxy);
569 vnxy = v_combine_high(vnz, va1);
570 _mm_storeu_pd(ptr_L, vnxy);
572 vnxy = v_combine_high(va2, va3);
573 _mm_storeu_pd(ptr_L, vnxy);
576 const __m128d verror = _mm_add_pd(vd, v_fma(vnx, vx, v_fma(vny, vy, _mm_mul_pd(vnz, vz))));
577 _mm_storeu_pd(ptr_error, verror);
580 float64x2_t vx, vy, vz;
581 v_load_deinterleave(ptr_point_cloud, vx, vy, vz);
583 float64x2_t va1 = vsubq_f64(vmulq_f64(vnz, vy), vmulq_f64(vny, vz));
584 float64x2_t va2 = vsubq_f64(vmulq_f64(vnx, vz), vmulq_f64(vnz, vx));
585 float64x2_t va3 = vsubq_f64(vmulq_f64(vny, vx), vmulq_f64(vnx, vy));
587 float64x2_t vnxy = v_combine_low(vnx, vny);
588 vst1q_f64(ptr_L, vnxy);
590 vnxy = v_combine_low(vnz, va1);
591 vst1q_f64(ptr_L, vnxy);
593 vnxy = v_combine_low(va2, va3);
594 vst1q_f64(ptr_L, vnxy);
597 vnxy = v_combine_high(vnx, vny);
598 vst1q_f64(ptr_L, vnxy);
600 vnxy = v_combine_high(vnz, va1);
601 vst1q_f64(ptr_L, vnxy);
603 vnxy = v_combine_high(va2, va3);
604 vst1q_f64(ptr_L, vnxy);
607 const float64x2_t verror = vaddq_f64(vd, v_fma(vnx, vx, v_fma(vny, vy, vmulq_f64(vnz, vz))));
608 vst1q_f64(ptr_error, verror);
619 double _a1 = (nz * y) - (ny * z);
620 double _a2 = (nx * z) - (nz * x);
621 double _a3 = (ny * x) - (nx * y);
624 L[(
unsigned int)(cpt / 3)][0] = nx;
625 L[(
unsigned int)(cpt / 3)][1] = ny;
626 L[(
unsigned int)(cpt / 3)][2] = nz;
627 L[(
unsigned int)(cpt / 3)][3] = _a1;
628 L[(
unsigned int)(cpt / 3)][4] = _a2;
629 L[(
unsigned int)(cpt / 3)][5] = _a3;
642 error[(
unsigned int)(cpt / 3)] = D + (normal.
t() * pt);
652 unsigned int idx = 0;
658 double _a1 = (nz * y) - (ny * z);
659 double _a2 = (nx * z) - (nz * x);
660 double _a3 = (ny * x) - (nx * y);
674 error[idx] = D + (normal.
t() * pt);
680 std::vector<vpImagePoint> &roiPts
681 #
if DEBUG_DISPLAY_DEPTH_DENSE
683 std::vector<std::vector<vpImagePoint> > &roiPts_vec
686 double &distanceToFace)
693 it->m_p1->changeFrame(cMo);
694 it->m_p2->changeFrame(cMo);
698 it->m_poly.changeFrame(cMo);
699 it->m_poly.computePolygonClipped(
m_cam);
701 if (it->m_poly.polyClipped.size() == 2 &&
709 std::vector<std::pair<vpPoint, vpPoint> > linesLst;
715 for (
unsigned int i = 0; i < linesLst.size(); i++) {
717 linesLst[i].second.project();
725 roiPts.push_back(ip1);
726 roiPts.push_back(ip2);
728 faceCentroid.
set_X(faceCentroid.
get_X() + linesLst[i].first.get_X() + linesLst[i].second.get_X());
729 faceCentroid.
set_Y(faceCentroid.
get_Y() + linesLst[i].first.get_Y() + linesLst[i].second.get_Y());
730 faceCentroid.
set_Z(faceCentroid.
get_Z() + linesLst[i].first.get_Z() + linesLst[i].second.get_Z());
732 #if DEBUG_DISPLAY_DEPTH_DENSE
733 std::vector<vpImagePoint> roiPts_;
734 roiPts_.push_back(ip1);
735 roiPts_.push_back(ip2);
736 roiPts_vec.push_back(roiPts_);
740 if (linesLst.empty()) {
741 distanceToFace = std::numeric_limits<double>::max();
743 faceCentroid.
set_X(faceCentroid.
get_X() / (2 * linesLst.size()));
744 faceCentroid.
set_Y(faceCentroid.
get_Y() / (2 * linesLst.size()));
745 faceCentroid.
set_Z(faceCentroid.
get_Z() / (2 * linesLst.size()));
748 sqrt(faceCentroid.
get_X() * faceCentroid.
get_X() + faceCentroid.
get_Y() * faceCentroid.
get_Y() +
758 std::vector<vpPoint> polygonsClipped;
761 if (polygonsClipped.empty()) {
762 distanceToFace = std::numeric_limits<double>::max();
766 for (
size_t i = 0; i < polygonsClipped.size(); i++) {
767 faceCentroid.
set_X(faceCentroid.
get_X() + polygonsClipped[i].get_X());
768 faceCentroid.
set_Y(faceCentroid.
get_Y() + polygonsClipped[i].get_Y());
769 faceCentroid.
set_Z(faceCentroid.
get_Z() + polygonsClipped[i].get_Z());
772 faceCentroid.
set_X(faceCentroid.
get_X() / polygonsClipped.size());
773 faceCentroid.
set_Y(faceCentroid.
get_Y() / polygonsClipped.size());
774 faceCentroid.
set_Z(faceCentroid.
get_Z() / polygonsClipped.size());
776 distanceToFace = sqrt(faceCentroid.
get_X() * faceCentroid.
get_X() + faceCentroid.
get_Y() * faceCentroid.
get_Y() +
780 #if DEBUG_DISPLAY_DEPTH_DENSE
781 roiPts_vec.push_back(roiPts);
788 bool displayFullModel)
790 std::vector<std::vector<double> > models =
793 for (
size_t i = 0; i < models.size(); i++) {
802 bool displayFullModel)
804 std::vector<std::vector<double> > models =
807 for (
size_t i = 0; i < models.size(); i++) {
840 bool displayFullModel)
842 std::vector<std::vector<double> > models;
850 std::vector<std::vector<double> > lineModels =
852 models.insert(models.end(), lineModels.begin(), lineModels.end());
874 if (dx <= std::numeric_limits<double>::epsilon() && dy <= std::numeric_limits<double>::epsilon() &&
875 dz <= std::numeric_limits<double>::epsilon())
887 (*it)->setCameraParameters(camera);
897 (*it)->useScanLine = v;
Type * data
Address of the first element of the data array.
Generic class defining intrinsic camera parameters.
void computeFov(const unsigned int &w, const unsigned int &h)
Implementation of column vector and the associated operations.
void resize(unsigned int i, bool flagNullify=true)
Class to define RGB colors available for display functionnalities.
static void displayLine(const vpImage< unsigned char > &I, const vpImagePoint &ip1, const vpImagePoint &ip2, const vpColor &color, unsigned int thickness=1, bool segment=true)
Implementation of an homogeneous matrix and operations on such kind of matrices.
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
unsigned int getWidth() const
unsigned int getHeight() const
Implementation of a matrix and operations on matrices.
vpMbScanLine & getMbScanLineRenderer()
bool isVisible(unsigned int i)
void computeScanLineQuery(const vpPoint &a, const vpPoint &b, std::vector< std::pair< vpPoint, vpPoint > > &lines, const bool &displayResults=false)
Manage the line of a polygon used in the model-based tracker.
void setIndex(unsigned int i)
vpPoint * p2
The second extremity.
std::list< int > Lindex_polygon
Index of the faces which contain the line.
void buildFrom(vpPoint &_p1, vpPoint &_p2, vpUniRand &rand_gen)
vpMbHiddenFaces< vpMbtPolygon > * hiddenface
Pointer to the list of faces.
std::vector< std::vector< double > > getModelForDisplay(unsigned int width, unsigned int height, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, bool displayFullModel=false)
bool useScanLine
Use scanline rendering.
vpPoint * p1
The first extremity.
void setCameraParameters(const vpCameraParameters &camera)
void setName(const std::string &line_name)
void setVisible(bool _isvisible)
void addPolygon(const int &index)
vpMbtPolygon & getPolygon()
double m_depthDenseFilteringMinDist
Minimum distance threshold.
vpMbHiddenFaces< vpMbtPolygon > * m_hiddenFace
Pointer to the list of faces.
void computeVisibilityDisplay()
virtual ~vpMbtFaceDepthDense()
bool m_isVisible
Visibility flag.
double m_distFarClip
Distance for near clipping.
std::vector< double > m_pointCloudFace
List of depth points inside the face.
vpPlane m_planeObject
Plane equation described in the object frame.
void display(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, const vpColor &col, unsigned int thickness=1, bool displayFullModel=false)
void setCameraParameters(const vpCameraParameters &camera)
bool computeDesiredFeatures(const vpHomogeneousMatrix &cMo, const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &point_cloud, unsigned int stepX, unsigned int stepY, const vpImage< bool > *mask=NULL)
std::vector< std::vector< double > > getModelForDisplay(unsigned int width, unsigned int height, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, bool displayFullModel=false)
void computeROI(const vpHomogeneousMatrix &cMo, unsigned int width, unsigned int height, std::vector< vpImagePoint > &roiPts, double &distanceToFace)
unsigned int getNbFeatures() const
bool samePoint(const vpPoint &P1, const vpPoint &P2) const
void computeInteractionMatrixAndResidu(const vpHomogeneousMatrix &cMo, vpMatrix &L, vpColVector &error)
void setScanLineVisibilityTest(bool v)
vpMbtPolygon * m_polygon
Polygon defining the face.
bool m_useScanLine
Scan line visibility.
bool m_isTrackedDepthDenseFace
Flag to define if the face should be tracked or not.
double m_depthDenseFilteringMaxDist
Maximum distance threshold.
std::vector< PolygonLine > m_polygonLines
Polygon lines used for scan-line visibility.
int m_depthDenseFilteringMethod
Method to use to consider or not the face.
@ DEPTH_OCCUPANCY_RATIO_FILTERING
unsigned int m_clippingFlag
Flags specifying which clipping to used.
std::vector< vpMbtDistanceLine * > m_listOfFaceLines
vpCameraParameters m_cam
Camera intrinsic parameters.
double m_depthDenseFilteringOccupancyRatio
Ratio between available depth points and theoretical number of points.
double m_distNearClip
Distance for near clipping.
void displayFeature(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, double scale=0.05, unsigned int thickness=1)
void addLine(vpPoint &p1, vpPoint &p2, vpMbHiddenFaces< vpMbtPolygon > *const faces, vpUniRand &rand_gen, int polygon=-1, std::string name="")
virtual bool isVisible(const vpHomogeneousMatrix &cMo, double alpha, const bool &modulo=false, const vpCameraParameters &cam=vpCameraParameters(), unsigned int width=0, unsigned int height=0)
static bool inMask(const vpImage< bool > *mask, unsigned int i, unsigned int j)
static void convertPoint(const vpCameraParameters &cam, const double &x, const double &y, double &u, double &v)
void changeFrame(const vpHomogeneousMatrix &cMo)
Class that defines a 3D point in the object frame and allows forward projection of a 3D point in the ...
double get_oX() const
Get the point oX coordinate in the object frame.
double get_Y() const
Get the point cY coordinate in the camera frame.
double get_oZ() const
Get the point oZ coordinate in the object frame.
void set_X(double cX)
Set the point cX coordinate in the camera frame.
void set_Y(double cY)
Set the point cY coordinate in the camera frame.
double get_Z() const
Get the point cZ coordinate in the camera frame.
void set_Z(double cZ)
Set the point cZ coordinate in the camera frame.
double get_oY() const
Get the point oY coordinate in the object frame.
double get_X() const
Get the point cX coordinate in the camera frame.
Implements a 3D polygon with render functionnalities like clipping.
void setFarClippingDistance(const double &dist)
void setNearClippingDistance(const double &dist)
void setClipping(const unsigned int &flags)
void getRoiClipped(const vpCameraParameters &cam, std::vector< vpImagePoint > &roi)
void getPolygonClipped(std::vector< std::pair< vpPoint, unsigned int > > &poly)
Defines a generic 2D polygon.
vpRect getBoundingBox() const
bool isInside(const vpImagePoint &iP, const PointInPolygonMethod &method=PnPolyRayCasting) const
Defines a rectangle in the plane.
void setRight(double pos)
void setBottom(double pos)
Class for generating random numbers with uniform probability density.
VISP_EXPORT bool checkSSE2()
VISP_EXPORT bool checkNeon()