Visual Servoing Platform  version 3.5.0 under development (2022-02-15)
vpMath Class Reference

#include <visp3/core/vpMath.h>

Public Member Functions

template<>
unsigned char saturate (char v)
 
template<>
unsigned char saturate (unsigned short v)
 
template<>
unsigned char saturate (int v)
 
template<>
unsigned char saturate (short v)
 
template<>
unsigned char saturate (unsigned int v)
 
template<>
unsigned char saturate (float v)
 
template<>
unsigned char saturate (double v)
 
template<>
char saturate (unsigned char v)
 
template<>
char saturate (unsigned short v)
 
template<>
char saturate (int v)
 
template<>
char saturate (short v)
 
template<>
char saturate (unsigned int v)
 
template<>
char saturate (float v)
 
template<>
char saturate (double v)
 
template<>
unsigned short saturate (char v)
 
template<>
unsigned short saturate (short v)
 
template<>
unsigned short saturate (int v)
 
template<>
unsigned short saturate (unsigned int v)
 
template<>
unsigned short saturate (float v)
 
template<>
unsigned short saturate (double v)
 
template<>
short saturate (unsigned short v)
 
template<>
short saturate (int v)
 
template<>
short saturate (unsigned int v)
 
template<>
short saturate (float v)
 
template<>
short saturate (double v)
 
template<>
int saturate (float v)
 
template<>
int saturate (double v)
 
template<>
unsigned int saturate (float v)
 
template<>
unsigned int saturate (double v)
 

Static Public Member Functions

static double deg (double rad)
 
static double rad (double deg)
 
static double sqr (double x)
 
static double fact (unsigned int x)
 
static long double comb (unsigned int n, unsigned int p)
 
static int round (double x)
 
static int() sign (double x)
 
static bool nul (double x, double s=0.001)
 
static bool equal (double x, double y, double s=0.001)
 
static bool greater (double x, double y, double s=0.001)
 
template<class Type >
static Type maximum (const Type &a, const Type &b)
 
template<class Type >
static Type minimum (const Type &a, const Type &b)
 
template<class Type >
static Type abs (const Type &x)
 
static double sinc (double x)
 
static double sinc (double sinx, double x)
 
static double mcosc (double cosx, double x)
 
static double msinc (double sinx, double x)
 
static double sigmoid (double x, double x0=0., double x1=1., double n=12.)
 
template<class Type >
static void swap (Type &a, Type &b)
 
static bool isNaN (double value)
 
static bool isNaN (float value)
 
static bool isInf (double value)
 
static bool isInf (float value)
 
static double lineFitting (const std::vector< vpImagePoint > &imPts, double &a, double &b, double &c)
 
template<typename _Tp >
static _Tp saturate (unsigned char v)
 
template<typename _Tp >
static _Tp saturate (char v)
 
template<typename _Tp >
static _Tp saturate (unsigned short v)
 
template<typename _Tp >
static _Tp saturate (short v)
 
template<typename _Tp >
static _Tp saturate (unsigned v)
 
template<typename _Tp >
static _Tp saturate (int v)
 
template<typename _Tp >
static _Tp saturate (float v)
 
template<typename _Tp >
static _Tp saturate (double v)
 
static double getMean (const std::vector< double > &v)
 
static double getMedian (const std::vector< double > &v)
 
static double getStdev (const std::vector< double > &v, bool useBesselCorrection=false)
 
static int modulo (int a, int n)
 

Detailed Description

Provides simple mathematics computation tools that are not available in the C mathematics library (math.h)

Author
Eric Marchand (Eric..nosp@m.Marc.nosp@m.hand@.nosp@m.iris.nosp@m.a.fr) Irisa / Inria Rennes

Definition at line 94 of file vpMath.h.

Member Function Documentation

◆ abs()

template<class Type >
static Type vpMath::abs ( const Type &  x)
inlinestatic

Find the absolute value of a number (or other).

Parameters
x: The number.
Returns
The absolute value of x
Examples:
testImageWarp.cpp.

Definition at line 160 of file vpMath.h.

Referenced by vpImageTools::imageDifferenceAbsolute(), vpImageTools::remap(), vpServo::secondaryTaskJointLimitAvoidance(), and vpMeNurbs::seekExtremities().

◆ comb()

long double vpMath::comb ( unsigned int  n,
unsigned int  p 
)
inlinestatic

Computes the number of combination of p elements inside n elements.

Parameters
n: total number of elements.
p: requested number of elements.
Returns
Combination number $ n! / ((n-p)! p!) $

Definition at line 232 of file vpMath.h.

Referenced by vpMomentCentered::compute(), vpMomentAlpha::compute(), vpFeatureMomentCentered::compute_Lmu_pq(), vpNurbs::computeCurveDersPoint(), and vpPixelMeterConversion::convertMoment().

◆ deg()

static double vpMath::deg ( double  rad)
inlinestatic

Convert an angle in radians into degrees.

Parameters
rad: Angle in radians.
Returns
Angle converted in degrees.
Examples:
calibrate-hand-eye.cpp, mbot-apriltag-2D-half-vs.cpp, mbot-apriltag-ibvs.cpp, mbot-apriltag-pbvs.cpp, moveBiclops.cpp, movePioneer.cpp, servoFrankaPBVS.cpp, servoPioneerPanSegment3D.cpp, servoPioneerPoint2DDepth.cpp, servoPioneerPoint2DDepthWithoutVpServo.cpp, sonarPioneerReader.cpp, testFrankaJointVelocityLimits.cpp, testGenericTracker.cpp, testGenericTrackerDepth.cpp, testMomentAlpha.cpp, testPose.cpp, testRobotAfma6Pose.cpp, testRobotFlirPtu.cpp, testRobotViper850.cpp, testRobotViper850Pose.cpp, testViper650.cpp, testViper850.cpp, trackMeLine.cpp, tutorial-hand-eye-calibration.cpp, tutorial-homography-from-points.cpp, tutorial-ibvs-4pts-wireframe-robot-afma6.cpp, tutorial-ibvs-4pts-wireframe-robot-viper.cpp, tutorial-mb-generic-tracker-live.cpp, tutorial-pose-from-points-live.cpp, and tutorial-pose-from-points-realsense-T265.cpp.

Definition at line 103 of file vpMath.h.

Referenced by vpPose::calculArbreDementhon(), vpHandEyeCalibration::calibrate(), vpMbGenericTracker::computeCurrentProjectionError(), vpMbTracker::computeCurrentProjectionError(), vpMbGenericTracker::computeProjectionError(), vpMbEdgeTracker::computeProjectionError(), vpAfma6::getInverseKinematics(), vpRobotFlirPtu::getNetworkHostName(), vpMeEllipse::leastSquareRobust(), vpMbDepthDenseTracker::loadConfigFile(), vpMbDepthNormalTracker::loadConfigFile(), vpMbEdgeKltTracker::loadConfigFile(), vpMbKltTracker::loadConfigFile(), vpMbEdgeTracker::loadConfigFile(), vpPose::poseDementhonNonPlan(), vpPose::poseDementhonPlan(), vpFeatureSegment::print(), vpPoseVector::print(), vpMeEllipse::printParameters(), vpServoData::save(), vpSimulatorAfma6::savePosFile(), vpRobotAfma4::savePosFile(), vpSimulatorViper850::savePosFile(), vpRobotAfma6::savePosFile(), vpRobotFranka::savePosFile(), vpRobotViper650::savePosFile(), vpRobotViper850::savePosFile(), vpRobotFlirPtu::setJointVelocity(), vpRobotKinova::setJointVelocity(), vpRobotKinova::setPosition(), vpRobotFlirPtu::setPosition(), vpRobotViper650::setPosition(), vpRobotViper850::setPosition(), vpRobotPioneer::setVelocity(), vpMeEllipse::track(), vpMbGenericTracker::track(), vpSimulatorAfma6::updateArticularPosition(), vpSimulatorViper850::updateArticularPosition(), and vpRobotBiclops::vpRobotBiclopsSpeedControlLoop().

◆ equal()

◆ fact()

double vpMath::fact ( unsigned int  x)
inlinestatic

Computes and returns x!

Parameters
x: parameter of factorial function.

Definition at line 217 of file vpMath.h.

◆ getMean()

◆ getMedian()

◆ getStdev()

double vpMath::getStdev ( const std::vector< double > &  v,
bool  useBesselCorrection = false 
)
static

◆ greater()

bool vpMath::greater ( double  x,
double  y,
double  s = 0.001 
)
inlinestatic

Compares $ x $ to $ y - s $.

Parameters
x: x value.
y: y value.
s: Tolerance threshold.
Returns
true if $ x > y - s $.

Definition at line 304 of file vpMath.h.

◆ isInf() [1/2]

bool vpMath::isInf ( double  value)
static

Returns whether a double is an infinity value (either positive infinity or negative infinity).

Parameters
value: Double number to check.
Returns
true if value is a plus or minus infinity (as defined by IEEE754 standard) and false otherwise.
Examples:
testMath.cpp.

Definition at line 129 of file vpMath.cpp.

◆ isInf() [2/2]

bool vpMath::isInf ( float  value)
static

Returns whether a float is an infinity value (either positive infinity or negative infinity).

Parameters
value: Double number to check.
Returns
true if value is a plus or minus infinity (as defined by IEEE754 standard) and false otherwise.

Definition at line 152 of file vpMath.cpp.

◆ isNaN() [1/2]

bool vpMath::isNaN ( double  value)
static

Check whether a double number is not a number (NaN) or not.

Parameters
value: Double number to check.
Returns
true if value is Not A Number (as defined by IEEE754 standard) and false otherwise.
Examples:
testMath.cpp, and tutorial-apriltag-detector-live-rgbd-structure-core.cpp.

Definition at line 85 of file vpMath.cpp.

Referenced by vpKeyPoint::compute3DForPointsOnCylinders(), vpMbtDistanceKltCylinder::computeInteractionMatrixAndResidu(), vpComedi::getPhyData(), vpMbtDistanceKltCylinder::init(), and vpPose::poseRansac().

◆ isNaN() [2/2]

bool vpMath::isNaN ( float  value)
static

Check whether a float number is not a number (NaN) or not.

Parameters
value: Float number to check.
Returns
true if value is Not A Number (as defined by IEEE754 standard) and false otherwise.

Definition at line 106 of file vpMath.cpp.

◆ lineFitting()

double vpMath::lineFitting ( const std::vector< vpImagePoint > &  imPts,
double &  a,
double &  b,
double &  c 
)
static

Compute the line equation using least-squares fitting that minimizes the cost function:

\[ \mathbf{E} = \sum_{i=1}^{n}\left ( ax_i + by_i - c \right )^2 \]

Parameters
imPts: Image points (size >= 3).
a: a coefficient.
b: b coefficient.
c: c coefficient.
Returns
The mean distance error (point-to-line distance) between the points and the fitted line.
Examples:
testLineFitting.cpp.

Definition at line 328 of file vpMath.cpp.

References vpException::dimensionError, vpMatrix::eigenValues(), vpImagePoint::get_u(), and vpImagePoint::get_v().

◆ maximum()

◆ mcosc()

double vpMath::mcosc ( double  cosx,
double  x 
)
static

Compute $ (1-cos(x))/x^2 $

Parameters
cosx: Value of cos(x).
x: Value of x.
Returns
$ (1-cosx)/x^2 $

Definition at line 177 of file vpMath.cpp.

Referenced by vpRotationMatrix::buildFrom(), vpExponentialMap::direct(), and vpExponentialMap::inverse().

◆ minimum()

◆ modulo()

int vpMath::modulo ( int  a,
int  n 
)
static

Compute the modified modulo:

  • modulo(11, 10) == 1 == 11 % 10
  • modulo(-1, 10) == 9
Parameters
a: The dividend.
n: The divisor.
Returns
The modified modulo of a mod n.

Definition at line 381 of file vpMath.cpp.

◆ msinc()

double vpMath::msinc ( double  sinx,
double  x 
)
static

Compute $ (1-sinc(x))/x^2 $ with $ sinc(x) = sinx / x $.

Parameters
sinx: value of sin(x).
x: Value of x.
Returns
$ (1-sinc(x))/x^2 $

Definition at line 194 of file vpMath.cpp.

Referenced by vpExponentialMap::direct(), and vpExponentialMap::inverse().

◆ nul()

bool vpMath::nul ( double  x,
double  s = 0.001 
)
inlinestatic

Compares $ | x | $ to $ s $.

Parameters
x: Value to test.
s: Tolerance threshold
Returns
true if $ | x | < s $.

Definition at line 286 of file vpMath.h.

Referenced by vpPose::computeRansacIterations(), vpQuaternionVector::inverse(), vpQuaternionVector::normalize(), vpQuaternionVector::operator/(), and vpImageTools::warpImage().

◆ rad()

static double vpMath::rad ( double  deg)
inlinestatic

Convert an angle in degrees into radian.

Parameters
deg: Angle in degrees.
Returns
Angle converted in radian.
Examples:
calibrate-hand-eye.cpp, exponentialMap.cpp, homographyHartleyDLT2DObject.cpp, homographyHLM2DObject.cpp, homographyHLM3DObject.cpp, homographyRansac2DObject.cpp, manServo4PointsDisplay.cpp, manServoMomentsSimple.cpp, manSimu4Dots.cpp, manSimu4Points.cpp, mbtEdgeKltTracking.cpp, mbtGenericTracking.cpp, mbtGenericTracking2.cpp, mbtGenericTrackingDepth.cpp, mbtGenericTrackingDepthOnly.cpp, mbtKltTracking.cpp, moveAfma4.cpp, moveBiclops.cpp, movePtu46.cpp, photometricVisualServoing.cpp, photometricVisualServoingWithoutVpServo.cpp, servoAfma62DhalfCamVelocity.cpp, servoAfma6Cylinder2DCamVelocity.cpp, servoAfma6Cylinder2DCamVelocitySecondaryTask.cpp, servoAfma6FourPoints2DCamVelocityLs_cur.cpp, servoAfma6FourPoints2DCamVelocityLs_des.cpp, servoAfma6Line2DCamVelocity.cpp, servoAfma6SquareLines2DCamVelocity.cpp, servoAfma6TwoLines2DCamVelocity.cpp, servoBebop2.cpp, servoFrankaPBVS.cpp, servoKinovaJacoJoint.cpp, servoMomentImage.cpp, servoMomentPoints.cpp, servoMomentPolygon.cpp, servoSimu3D_cdMc_CamVelocity.cpp, servoSimu3D_cdMc_CamVelocityWithoutVpServo.cpp, servoSimu3D_cMcd_CamVelocity.cpp, servoSimu3D_cMcd_CamVelocityWithoutVpServo.cpp, servoSimu4Points.cpp, servoSimuAfma6FourPoints2DCamVelocity.cpp, servoSimuCircle2DCamVelocityDisplay.cpp, servoSimuCylinder.cpp, servoSimuCylinder2DCamVelocityDisplay.cpp, servoSimuCylinder2DCamVelocityDisplaySecondaryTask.cpp, servoSimuFourPoints2DCamVelocityDisplay.cpp, servoSimuFourPoints2DPolarCamVelocityDisplay.cpp, servoSimuLine2DCamVelocityDisplay.cpp, servoSimuPoint2DhalfCamVelocity1.cpp, servoSimuPoint2DhalfCamVelocity2.cpp, servoSimuPoint2DhalfCamVelocity3.cpp, servoSimuSphere.cpp, servoSimuSphere2DCamVelocityDisplaySecondaryTask.cpp, servoSimuSquareLine2DCamVelocityDisplay.cpp, servoSimuThetaUCamVelocity.cpp, servoSimuViper850FourPoints2DCamVelocity.cpp, servoViper850FourPoints2DArtVelocityLs_cur.cpp, servoViper850FourPoints2DCamVelocityLs_cur.cpp, servoViper850FourPointsKinect.cpp, simulateCircle2DCamVelocity.cpp, simulateFourPoints2DCartesianCamVelocity.cpp, simulateFourPoints2DPolarCamVelocity.cpp, sonarPioneerReader.cpp, testDisplacement.cpp, testFeatureSegment.cpp, testFindMatch.cpp, testFrankaJointVelocity-2.cpp, testFrankaJointVelocity-3.cpp, testFrankaJointVelocity.cpp, testFrankaJointVelocityLimits.cpp, testGenericTracker.cpp, testGenericTrackerDepth.cpp, testImageWarp.cpp, testKalmanAcceleration.cpp, testKalmanVelocity.cpp, testKeyPoint-2.cpp, testKeyPoint-4.cpp, testMatrix.cpp, testPose.cpp, testPoseFeatures.cpp, testPoseVector.cpp, testRobotBebop2.cpp, testRobotFlirPtu.cpp, testRobotViper650-frames.cpp, testRobotViper850-frames.cpp, testViper650.cpp, testViper850.cpp, testVirtuoseWithGlove.cpp, tutorial-detection-object-mbt-deprecated.cpp, tutorial-detection-object-mbt.cpp, tutorial-detection-object-mbt2-deprecated.cpp, tutorial-detection-object-mbt2.cpp, tutorial-homography-from-points.cpp, tutorial-ibvs-4pts-display.cpp, tutorial-ibvs-4pts-image-tracking.cpp, tutorial-ibvs-4pts-ogre-tracking.cpp, tutorial-ibvs-4pts-ogre.cpp, tutorial-ibvs-4pts-plotter-continuous-gain-adaptive.cpp, tutorial-ibvs-4pts-plotter-gain-adaptive.cpp, tutorial-ibvs-4pts-plotter.cpp, tutorial-ibvs-4pts-wireframe-camera.cpp, tutorial-ibvs-4pts-wireframe-robot-afma6.cpp, tutorial-ibvs-4pts-wireframe-robot-viper.cpp, tutorial-ibvs-4pts.cpp, tutorial-image-simulator.cpp, tutorial-mb-edge-tracker.cpp, tutorial-mb-generic-tracker-apriltag-rs2.cpp, tutorial-mb-generic-tracker-apriltag-webcam.cpp, tutorial-mb-generic-tracker-full.cpp, tutorial-mb-hybrid-tracker.cpp, tutorial-mb-klt-tracker.cpp, tutorial-mb-tracker-full.cpp, and wireframeSimulator.cpp.

Definition at line 110 of file vpMath.h.

Referenced by vpVirtualGrabber::acquire(), vpMbTracker::addPolygon(), vpMbTracker::addProjectionErrorPolygon(), vpMbGenericTracker::computeProjectionError(), vpRobotViper650::get_eJe(), vpRobotViper850::get_eJe(), vpAfma6::getInverseKinematics(), vpViper::getInverseKinematicsWrist(), vpRobotKinova::getJointPosition(), vpRobotFlirPtu::getNetworkHostName(), vpRobotPioneer::getVelocity(), vpViper650::init(), vpViper850::init(), vpAfma6::init(), vpSimulatorAfma6::init(), vpSimulatorViper850::init(), vpSimulatorAfma6::initDisplay(), vpSimulatorViper850::initDisplay(), vpMbtPolygon::isVisible(), vpMeEllipse::leastSquareRobust(), vpMbTracker::loadCAOModel(), vpMbDepthDenseTracker::loadConfigFile(), vpMbDepthNormalTracker::loadConfigFile(), vpMbEdgeKltTracker::loadConfigFile(), vpMbKltTracker::loadConfigFile(), vpMbEdgeTracker::loadConfigFile(), vpWireFrameSimulator::navigation(), vpMeEllipse::plugHoles(), vpSimulatorAfma6::readPosFile(), vpRobotAfma4::readPosFile(), vpRobotAfma6::readPosFile(), vpRobotFranka::readPosFile(), vpMbDepthDenseTracker::resetTracker(), vpMbDepthNormalTracker::resetTracker(), vpMbGenericTracker::resetTracker(), vpMbKltTracker::resetTracker(), vpMbEdgeTracker::resetTracker(), vpMeEllipse::sample(), vpMeEllipse::track(), vpMbGenericTracker::track(), vpRobotBiclops::vpRobotBiclopsSpeedControlLoop(), vpRobotCamera::vpRobotCamera(), vpSickLDMRS::vpSickLDMRS(), vpSimulatorCamera::vpSimulatorCamera(), vpViper::vpViper(), vpViper650::vpViper650(), vpViper850::vpViper850(), vpWireFrameSimulator::vpWireFrameSimulator(), and vpPioneer::~vpPioneer().

◆ round()

◆ saturate() [1/37]

template<typename _Tp >
static _Tp vpMath::saturate ( unsigned char  v)
inlinestatic

Definition at line 191 of file vpMath.h.

◆ saturate() [2/37]

template<typename _Tp >
static _Tp vpMath::saturate ( char  v)
inlinestatic

Definition at line 192 of file vpMath.h.

◆ saturate() [3/37]

template<typename _Tp >
static _Tp vpMath::saturate ( unsigned short  v)
inlinestatic

Definition at line 193 of file vpMath.h.

◆ saturate() [4/37]

template<typename _Tp >
static _Tp vpMath::saturate ( short  v)
inlinestatic

Definition at line 194 of file vpMath.h.

◆ saturate() [5/37]

template<typename _Tp >
static _Tp vpMath::saturate ( unsigned  v)
inlinestatic

Definition at line 195 of file vpMath.h.

◆ saturate() [6/37]

template<typename _Tp >
static _Tp vpMath::saturate ( int  v)
inlinestatic

Definition at line 196 of file vpMath.h.

◆ saturate() [7/37]

template<typename _Tp >
static _Tp vpMath::saturate ( float  v)
inlinestatic

Definition at line 197 of file vpMath.h.

◆ saturate() [8/37]

template<typename _Tp >
static _Tp vpMath::saturate ( double  v)
inlinestatic

Definition at line 198 of file vpMath.h.

◆ saturate() [9/37]

template<>
unsigned char vpMath::saturate ( char  v)
inline

Definition at line 329 of file vpMath.h.

◆ saturate() [10/37]

template<>
unsigned char vpMath::saturate ( unsigned short  v)
inline

Definition at line 342 of file vpMath.h.

◆ saturate() [11/37]

template<>
unsigned char vpMath::saturate ( int  v)
inline

Definition at line 347 of file vpMath.h.

◆ saturate() [12/37]

template<>
unsigned char vpMath::saturate ( short  v)
inline

Definition at line 352 of file vpMath.h.

◆ saturate() [13/37]

template<>
unsigned char vpMath::saturate ( unsigned int  v)
inline

Definition at line 354 of file vpMath.h.

◆ saturate() [14/37]

template<>
unsigned char vpMath::saturate ( float  v)
inline

Definition at line 359 of file vpMath.h.

References round().

◆ saturate() [15/37]

template<>
unsigned char vpMath::saturate ( double  v)
inline

Definition at line 365 of file vpMath.h.

References round().

◆ saturate() [16/37]

template<>
char vpMath::saturate ( unsigned char  v)
inline

Definition at line 372 of file vpMath.h.

◆ saturate() [17/37]

template<>
char vpMath::saturate ( unsigned short  v)
inline

Definition at line 374 of file vpMath.h.

◆ saturate() [18/37]

template<>
char vpMath::saturate ( int  v)
inline

Definition at line 379 of file vpMath.h.

◆ saturate() [19/37]

template<>
char vpMath::saturate ( short  v)
inline

Definition at line 384 of file vpMath.h.

◆ saturate() [20/37]

template<>
char vpMath::saturate ( unsigned int  v)
inline

Definition at line 386 of file vpMath.h.

◆ saturate() [21/37]

template<>
char vpMath::saturate ( float  v)
inline

Definition at line 391 of file vpMath.h.

References round().

◆ saturate() [22/37]

template<>
char vpMath::saturate ( double  v)
inline

Definition at line 397 of file vpMath.h.

References round().

◆ saturate() [23/37]

template<>
unsigned short vpMath::saturate ( char  v)
inline

Definition at line 404 of file vpMath.h.

◆ saturate() [24/37]

template<>
unsigned short vpMath::saturate ( short  v)
inline

Definition at line 417 of file vpMath.h.

◆ saturate() [25/37]

template<>
unsigned short vpMath::saturate ( int  v)
inline

Definition at line 422 of file vpMath.h.

◆ saturate() [26/37]

template<>
unsigned short vpMath::saturate ( unsigned int  v)
inline

Definition at line 427 of file vpMath.h.

◆ saturate() [27/37]

template<>
unsigned short vpMath::saturate ( float  v)
inline

Definition at line 432 of file vpMath.h.

References round().

◆ saturate() [28/37]

template<>
unsigned short vpMath::saturate ( double  v)
inline

Definition at line 438 of file vpMath.h.

References round().

◆ saturate() [29/37]

template<>
short vpMath::saturate ( unsigned short  v)
inline

Definition at line 445 of file vpMath.h.

◆ saturate() [30/37]

template<>
short vpMath::saturate ( int  v)
inline

Definition at line 446 of file vpMath.h.

◆ saturate() [31/37]

template<>
short vpMath::saturate ( unsigned int  v)
inline

Definition at line 450 of file vpMath.h.

◆ saturate() [32/37]

template<>
short vpMath::saturate ( float  v)
inline

Definition at line 454 of file vpMath.h.

References round().

◆ saturate() [33/37]

template<>
short vpMath::saturate ( double  v)
inline

Definition at line 459 of file vpMath.h.

References round().

◆ saturate() [34/37]

template<>
int vpMath::saturate ( float  v)
inline

Definition at line 466 of file vpMath.h.

References round().

◆ saturate() [35/37]

template<>
int vpMath::saturate ( double  v)
inline

Definition at line 468 of file vpMath.h.

References round().

◆ saturate() [36/37]

template<>
unsigned int vpMath::saturate ( float  v)
inline

Definition at line 473 of file vpMath.h.

References round().

◆ saturate() [37/37]

template<>
unsigned int vpMath::saturate ( double  v)
inline

Definition at line 475 of file vpMath.h.

References round().

◆ sigmoid()

double vpMath::sigmoid ( double  x,
double  x0 = 0.,
double  x1 = 1.,
double  n = 12. 
)
inlinestatic

Sigmoid function between [x0,x1] with $ s(x)=0 if x\le x0$ and $ s(x)=1 if x \ge x1 $

Parameters
x: Value of x.
x0: Lower bound (default 0).
x1: Upper bound (default 1).
n: Degree of the exponential (default 12).
Returns
Sigmoid value $1/(1+exp(-n*((x-x0)/(x1-x0)-0.5)))$

Definition at line 317 of file vpMath.h.

◆ sign()

static int() vpMath::sign ( double  x)
inlinestatic

◆ sinc() [1/2]

double vpMath::sinc ( double  x)
static

Compute sinus cardinal $ \frac{sin(x)}{x} $.

Parameters
x: Value of x.
Returns
Sinus cardinal.

Definition at line 210 of file vpMath.cpp.

Referenced by vpRotationMatrix::buildFrom(), vpThetaUVector::buildFrom(), vpMatrix::computeCovarianceMatrixVVS(), vpExponentialMap::direct(), vpFeatureThetaU::interaction(), and vpExponentialMap::inverse().

◆ sinc() [2/2]

double vpMath::sinc ( double  sinx,
double  x 
)
static

Compute sinus cardinal $ \frac{sin(x)}{x}$.

Parameters
sinx: Value of sin(x).
x: Value of x.
Returns
Sinus cardinal.

Definition at line 226 of file vpMath.cpp.

◆ sqr()

static double vpMath::sqr ( double  x)
inlinestatic

Compute x square value.

Returns
Square value $ x^2 $.
Examples:
servoSimuSphere.cpp, servoViper850Point2DArtVelocity-jointAvoidance-gpa.cpp, testColorConversion.cpp, testRobust.cpp, and tutorial-klt-tracker-with-reinit.cpp.

Definition at line 116 of file vpMath.h.

Referenced by vpMbTracker::addPolygon(), vpMbTracker::addProjectionErrorPolygon(), vpMatrix::computeCovarianceMatrixVVS(), vpHomography::computeDisplacement(), vpMbtDistanceCircle::computeInteractionMatrixError(), vpCircle::computeIntersectionPoint(), vpPoseFeatures::computePose(), vpPose::computeResidual(), vpPose::computeResidualDementhon(), vpCalibration::computeStdDeviation(), vpCalibration::computeStdDeviation_dist(), vpMbDepthDenseTracker::computeVVS(), vpMbDepthNormalTracker::computeVVS(), vpMbEdgeKltTracker::computeVVS(), vpMbGenericTracker::computeVVS(), vpMbEdgeTracker::computeVVS(), vpMbEdgeTracker::computeVVSInit(), vpMeterPixelConversion::convertEllipse(), vpPixelMeterConversion::convertLine(), vpMeterPixelConversion::convertLine(), vpPixelMeterConversion::convertPoint(), vpMeterPixelConversion::convertPoint(), vpPose::coplanar(), vpFeatureBuilder::create(), vpDot2::defineDots(), vpDisplayX::displayArrow(), vpDisplayGTK::displayArrow(), vpDisplayOpenCV::displayArrow(), vpDisplayOpenCV::displayDotLine(), vpCalibration::displayGrid(), vpMeSite::distance(), vpImagePoint::distance(), vpImageDraw::drawArrow(), vpImageDraw::drawDottedLine(), vpMbtFaceDepthNormal::estimateFeatures(), vpImageFilter::getGaussianDerivativeKernel(), vpImageFilter::getGaussianKernel(), vpViper::getInverseKinematicsWrist(), vpImageTools::initUndistortMap(), vpImageTools::integralImage(), vpFeatureEllipse::interaction(), vpFeatureThetaU::interaction(), vpRotationMatrix::isARotationMatrix(), vpScale::KernelDensityGradient(), vpScale::KernelDensityGradient_EPANECHNIKOV(), vpMeLine::leastSquare(), vpMeNurbs::localReSample(), vpScale::MeanShift(), vpRobust::MEstimator(), vpPose::poseVirtualVSrobust(), vpSphere::projection(), vpCircle::projection(), vpNurbs::removeCurveKnot(), vpMeLine::reSample(), vpMeLine::sample(), vpMeNurbs::sample(), vpMeLine::seekExtremities(), vpMeNurbs::seekExtremitiesCanny(), vpRobust::simultMEstimator(), vpMeSite::sqrDistance(), vpImagePoint::sqrDistance(), vpMeNurbs::supressNearPoints(), vpImageTools::templateMatching(), vpMeSite::track(), vpMbGenericTracker::track(), and vpImageTools::undistort().

◆ swap()

template<class Type >
static void vpMath::swap ( Type &  a,
Type &  b 
)
inlinestatic

Exchange two numbers.

Parameters
aFirst number to exchange.
bSecond number to exchange

Definition at line 177 of file vpMath.h.