Visual Servoing Platform  version 3.2.0 under development (2019-01-22)
vpImagePoint Class Reference

#include <visp3/core/vpImagePoint.h>

Public Member Functions

 vpImagePoint ()
 
 vpImagePoint (double ii, double jj)
 
 vpImagePoint (const vpImagePoint &ip)
 
virtual ~vpImagePoint ()
 
vpImagePointoperator= (const vpImagePoint &ip)
 
vpImagePointoperator= (const vpImagePoint &&ip)
 
vpImagePointoperator+= (const vpImagePoint &ip)
 
vpImagePointoperator-= (const vpImagePoint &ip)
 
vpImagePointoperator/= (const double scale)
 
vpImagePointoperator*= (const double scale)
 
void set_i (const double ii)
 
void set_j (const double jj)
 
void set_ij (const double ii, const double jj)
 
double get_i () const
 
double get_j () const
 
void set_u (const double u)
 
void set_v (const double v)
 
void set_uv (const double u, const double v)
 
double get_u () const
 
double get_v () const
 
bool inRectangle (const vpRect &rect) const
 

Static Public Member Functions

static double distance (const vpImagePoint &iP1, const vpImagePoint &iP2)
 
static vpRect getBBox (const std::vector< vpImagePoint > &ipVec)
 
static double sqrDistance (const vpImagePoint &iP1, const vpImagePoint &iP2)
 

Friends

VISP_EXPORT bool operator== (const vpImagePoint &ip1, const vpImagePoint &ip2)
 
VISP_EXPORT bool operator!= (const vpImagePoint &ip1, const vpImagePoint &ip2)
 
VISP_EXPORT vpImagePoint operator+= (const vpImagePoint &ip1, const vpImagePoint &ip2)
 
VISP_EXPORT vpImagePoint operator+ (const vpImagePoint &ip1, const vpImagePoint &ip2)
 
VISP_EXPORT vpImagePoint operator+ (const vpImagePoint &ip1, const int offset)
 
VISP_EXPORT vpImagePoint operator+ (const vpImagePoint &ip1, const unsigned int offset)
 
VISP_EXPORT vpImagePoint operator+ (const vpImagePoint &ip1, const double offset)
 
VISP_EXPORT vpImagePoint operator- (const vpImagePoint &ip1, const vpImagePoint &ip2)
 
VISP_EXPORT vpImagePoint operator- (const vpImagePoint &ip1, const int offset)
 
VISP_EXPORT vpImagePoint operator- (const vpImagePoint &ip1, const unsigned int offset)
 
VISP_EXPORT vpImagePoint operator- (const vpImagePoint &ip1, const double offset)
 
VISP_EXPORT vpImagePoint operator* (const vpImagePoint &ip1, const double scale)
 
VISP_EXPORT vpImagePoint operator/ (const vpImagePoint &ip1, const double scale)
 
VISP_EXPORT std::ostream & operator<< (std::ostream &os, const vpImagePoint &ip)
 

Detailed Description

Class that defines a 2D point in an image. This class is useful for image processing and stores only the 2D coordinates given in sub-pixel.

Warning
If you want to define a point thanks to its coordinates given in meter in the object frame, the camera frame or the image plane, you have to use the class vpPoint.

In this class, the 2D coordinates are not necessary integer values. It is easy to manipulate the given coordinates in the two frames used in ViSP : the (i,j) coordinates and the (u,v) coordinates. The two following images illustrate the two coordinate systems.

vpImagePoint.gif
Warning
An instance of the vpImagePoint class corresponds to a particular point. Thus, if you change the point coordinate using the method set_i(const double i), it produces the same effect than if you used the method set_v(const double v). These two methods change the same private attribute. It is also true for the two methods set_j(const double j) and set_u(const double u).
Examples:
AROgre.cpp, AROgreBasic.cpp, BSpline.cpp, displayD3D.cpp, displayGTK.cpp, displayOpenCV.cpp, displayX.cpp, displayXMulti.cpp, fernClassifier.cpp, keyPointSurf.cpp, manDisplay.cpp, mbot-apriltag-2D-half-vs.cpp, planarObjectDetector.cpp, poseVirtualVS.cpp, servoAfma4Point2DArtVelocity.cpp, servoAfma4Point2DCamVelocity.cpp, servoAfma4Point2DCamVelocityKalman.cpp, servoAfma62DhalfCamVelocity.cpp, servoAfma6Ellipse2DCamVelocity.cpp, servoAfma6FourPoints2DArtVelocity.cpp, servoAfma6FourPoints2DCamVelocityInteractionCurrent.cpp, servoAfma6FourPoints2DCamVelocityInteractionDesired.cpp, servoAfma6Point2DArtVelocity.cpp, servoAfma6Point2DCamVelocity.cpp, servoAfma6Points2DCamVelocityEyeToHand.cpp, servoAfma6Segment2DCamVelocity.cpp, servoPtu46Point2DArtVelocity.cpp, servoSimuFourPoints2DPolarCamVelocityDisplay.cpp, servoViper650FourPoints2DArtVelocityInteractionCurrent.cpp, servoViper650FourPoints2DCamVelocityInteractionCurrent-SR300.cpp, servoViper650FourPoints2DCamVelocityInteractionCurrent.cpp, servoViper650Point2DCamVelocity.cpp, servoViper850FourPoints2DArtVelocityInteractionCurrent.cpp, servoViper850FourPoints2DArtVelocityInteractionDesired.cpp, servoViper850FourPoints2DCamVelocityInteractionCurrent.cpp, servoViper850FourPointsKinect.cpp, servoViper850Point2DArtVelocity-jointAvoidance-basic.cpp, servoViper850Point2DArtVelocity-jointAvoidance-gpa.cpp, servoViper850Point2DArtVelocity-jointAvoidance-large.cpp, servoViper850Point2DArtVelocity.cpp, servoViper850Point2DCamVelocity.cpp, servoViper850Point2DCamVelocityKalman.cpp, SickLDMRS-Process.cpp, templateTracker.cpp, testClick.cpp, testConnectedComponents.cpp, testConvert.cpp, testDisplays.cpp, testFloodFill.cpp, testGenericTracker.cpp, testGenericTrackerDepth.cpp, testImageNormalizedCorrelation.cpp, testImagePoint.cpp, testImageTemplateMatching.cpp, testKeyPoint-2.cpp, testKeyPoint-3.cpp, testKeyPoint-4.cpp, testKeyPoint-5.cpp, testKeyPoint-6.cpp, testKeyPoint.cpp, testMouseEvent.cpp, testNurbs.cpp, testRobotAfma6Pose.cpp, testRobotViper850Pose.cpp, testTrackDot.cpp, testVirtuoseWithGlove.cpp, trackDot.cpp, trackDot2.cpp, trackDot2WithAutoDetection.cpp, trackMeCircle.cpp, trackMeEllipse.cpp, trackMeLine.cpp, trackMeNurbs.cpp, tutorial-apriltag-detector.cpp, tutorial-autothreshold.cpp, tutorial-barcode-detector-live.cpp, tutorial-barcode-detector.cpp, tutorial-blob-tracker-live-firewire.cpp, tutorial-blob-tracker-live-v4l2.cpp, tutorial-brightness-adjustment.cpp, tutorial-chessboard-pose.cpp, tutorial-detection-object-mbt2-deprecated.cpp, tutorial-detection-object-mbt2.cpp, tutorial-flood-fill.cpp, tutorial-homography-from-points.cpp, tutorial-ibvs-4pts-display.cpp, tutorial-ibvs-4pts-wireframe-camera.cpp, tutorial-ibvs-4pts-wireframe-robot-afma6.cpp, tutorial-ibvs-4pts-wireframe-robot-viper.cpp, tutorial-image-viewer.cpp, tutorial-klt-tracker-live-v4l2.cpp, tutorial-klt-tracker.cpp, tutorial-matching-keypoint-homography.cpp, tutorial-matching-keypoint-SIFT.cpp, tutorial-matching-keypoint.cpp, tutorial-matching-surf-deprecated.cpp, tutorial-matching-surf-homography-deprecated.cpp, tutorial-pose-from-points-image.cpp, and tutorial-pose-from-qrcode-image.cpp.

Definition at line 88 of file vpImagePoint.h.

Constructor & Destructor Documentation

vpImagePoint::vpImagePoint ( )
inline

Default constructor that initialize the coordinates of the image point to zero.

Definition at line 95 of file vpImagePoint.h.

vpImagePoint::vpImagePoint ( double  ii,
double  jj 
)
inline

Default constructor that initialize the coordinates of the image thanks to the parameters $ ii $ and $ jj $.

Definition at line 100 of file vpImagePoint.h.

vpImagePoint::vpImagePoint ( const vpImagePoint ip)
inline

Copy constructor.

Initialize the coordinates of the image point with ip.

Parameters
ip: An image point.

Definition at line 108 of file vpImagePoint.h.

virtual vpImagePoint::~vpImagePoint ( )
inlinevirtual

Destructor.

Definition at line 110 of file vpImagePoint.h.

Member Function Documentation

static double vpImagePoint::distance ( const vpImagePoint iP1,
const vpImagePoint iP2 
)
inlinestatic

Compute the distance $ |iP1 - iP2| = \sqrt{(i_1-i_2)^2+(j_1-j_2)^2} $

Parameters
iP1: First point
iP2: Second point
Returns
the distance between the two points.
Examples:
testImageNormalizedCorrelation.cpp.

Definition at line 285 of file vpImagePoint.h.

References get_i(), get_j(), and vpMath::sqr().

Referenced by vpDisplayGTK::displayArrow(), vpDisplayX::displayArrow(), vpDisplayOpenCV::displayArrow(), vpNurbs::globalCurveInterp(), vpMeNurbs::seekExtremities(), vpMeNurbs::track(), and vpMeNurbs::updateDelta().

double vpImagePoint::get_i ( ) const
inline

Gets the point coordinate corresponding to the $ i $ axes in the frame (i,j).

Returns
The value of the coordinate along the $ i $ axes.
See also
get_j(), get_u(), get_v()
Examples:
keyPointSurf.cpp, and tutorial-flood-fill.cpp.

Definition at line 204 of file vpImagePoint.h.

Referenced by vpTriangle::buildFrom(), vpNurbs::computeCurveDersPoint(), vpImageTools::crop(), vpMeNurbs::display(), vpMeEllipse::display(), vpDisplayGTK::displayArrow(), vpDisplayX::displayArrow(), vpDisplayOpenCV::displayArrow(), vpDisplayGTK::displayCross(), vpDisplayX::displayCross(), vpDisplayOpenCV::displayCross(), vpDisplayOpenCV::displayDotLine(), vpDisplayGTK::displayImageROI(), vpDisplayX::displayImageROI(), vpDisplayOpenCV::displayImageROI(), vpKeyPoint::displayMatching(), vpMbtDistanceKltCylinder::displayPrimitive(), vpMbtDistanceKltPoints::displayPrimitive(), vpDisplayWin32::displayRectangle(), distance(), vpImageTools::extract(), vp::findContours(), vp::floodFill(), vpPolygon3D::getNbCornerInsideImage(), vpImage< double >::getValue(), vpImage< vpRGBa >::getValue(), vpImage< Type >::getValue(), vpPolygon::init(), vpMbtDistanceLine::initMovingEdge(), vpMbtDistanceCylinder::initMovingEdge(), vpMeEllipse::initTracking(), vpMeLine::initTracking(), vpDot2::initTracking(), vpDot::initTracking(), vpImage< Type >::insert(), vpImageTools::interpolate(), vpTriangle::inTriangle(), vpTemplateTrackerTriangle::inTriangle(), vpRectOriented::isInside(), vpPolygon::isInside(), vpRect::isInside(), vpWireFrameSimulator::navigation(), vpImage< bool >::operator()(), vpRectOriented::operator=(), vpMeTracker::outOfImage(), vpMeEllipse::printParameters(), vpNurbs::removeCurveKnot(), vpMeNurbs::seekExtremitiesCanny(), vpRectOriented::setOrientation(), vpRectOriented::setPoints(), vpRectOriented::setSize(), sqrDistance(), vpMeEllipse::track(), vpMbtDistanceLine::updateMovingEdge(), vpMbtDistanceCylinder::updateMovingEdge(), vpRectOriented::vpRectOriented(), vpXmlParserRectOriented::writeMainClass(), and vpMeEllipse::~vpMeEllipse().

double vpImagePoint::get_j ( ) const
inline

Gets the point coordinate corresponding to the $ j $ axes in the frame (i,j).

Returns
The value of the coordinate along the $ j $ axes.
See also
get_i(), get_u(), get_v()
Examples:
keyPointSurf.cpp, and tutorial-flood-fill.cpp.

Definition at line 215 of file vpImagePoint.h.

Referenced by vpTriangle::buildFrom(), vpNurbs::computeCurveDersPoint(), vpImageTools::crop(), vpMeNurbs::display(), vpMeEllipse::display(), vpDisplayGTK::displayArrow(), vpDisplayX::displayArrow(), vpDisplayOpenCV::displayArrow(), vpDisplayGTK::displayCross(), vpDisplayX::displayCross(), vpDisplayOpenCV::displayCross(), vpDisplayOpenCV::displayDotLine(), vpDisplayGTK::displayImageROI(), vpDisplayX::displayImageROI(), vpDisplayOpenCV::displayImageROI(), vpKeyPoint::displayMatching(), vpMbtDistanceKltCylinder::displayPrimitive(), vpMbtDistanceKltPoints::displayPrimitive(), vpDisplayWin32::displayRectangle(), distance(), vpImageTools::extract(), vp::findContours(), vp::floodFill(), vpPolygon3D::getNbCornerInsideImage(), vpImage< double >::getValue(), vpImage< vpRGBa >::getValue(), vpImage< Type >::getValue(), vpPolygon::init(), vpMbtDistanceLine::initMovingEdge(), vpMbtDistanceCylinder::initMovingEdge(), vpMeEllipse::initTracking(), vpMeLine::initTracking(), vpDot2::initTracking(), vpDot::initTracking(), vpImage< Type >::insert(), vpImageTools::interpolate(), vpTriangle::inTriangle(), vpTemplateTrackerTriangle::inTriangle(), vpRectOriented::isInside(), vpPolygon::isInside(), vpRect::isInside(), vpWireFrameSimulator::navigation(), vpImage< bool >::operator()(), vpRectOriented::operator=(), vpMeTracker::outOfImage(), vpMeEllipse::printParameters(), vpNurbs::removeCurveKnot(), vpMeNurbs::seekExtremitiesCanny(), vpRectOriented::setOrientation(), vpRectOriented::setPoints(), vpRectOriented::setSize(), sqrDistance(), vpMeEllipse::track(), vpMbtDistanceLine::updateMovingEdge(), vpMbtDistanceCylinder::updateMovingEdge(), vpRectOriented::vpRectOriented(), vpXmlParserRectOriented::writeMainClass(), and vpMeEllipse::~vpMeEllipse().

double vpImagePoint::get_u ( ) const
inline

Gets the point coordinate corresponding to the $ u $ axes in the frame (u,v).

Returns
The value of the coordinate along the $ u $ axes.
See also
get_i(), get_j(), get_v()
Examples:
servoAfma4Point2DCamVelocityKalman.cpp, testConvert.cpp, trackDot.cpp, trackDot2.cpp, trackDot2WithAutoDetection.cpp, tutorial-detection-object-mbt2-deprecated.cpp, tutorial-detection-object-mbt2.cpp, tutorial-flood-fill.cpp, tutorial-klt-tracker-live-v4l2.cpp, and tutorial-klt-tracker.cpp.

Definition at line 263 of file vpImagePoint.h.

Referenced by vpCalibration::computeStdDeviation(), vpCalibration::computeStdDeviation_dist(), vpPixelMeterConversion::convertPoint(), vpDot2::defineDots(), vpDisplayGTK::displayCharString(), vpDisplayX::displayCharString(), vpDisplayOpenCV::displayCharString(), vpDisplayGTK::displayCircle(), vpDisplayX::displayCircle(), vpDisplayOpenCV::displayCircle(), vpCalibration::displayData(), vpDisplayGTK::displayDotLine(), vpDisplayX::displayDotLine(), vpDisplayX::displayImageROI(), vpDisplayGTK::displayLine(), vpDisplayX::displayLine(), vpDisplayOpenCV::displayLine(), vpDisplayGTK::displayPoint(), vpDisplayX::displayPoint(), vpDisplayOpenCV::displayPoint(), vpDisplayGTK::displayRectangle(), vpDisplayX::displayRectangle(), vpDisplayOpenCV::displayRectangle(), vpDisplayWin32::flushDisplayROI(), vpDisplayX::flushDisplayROI(), vpDot2::getDistance(), vpDot2::getFreemanChain(), vpTemplateTrackerTriangle::init(), vpImageSimulator::init(), vpPolygon::isInside(), vpRect::moveCenter(), vpDot::operator==(), vpHomography::project(), vpHomography::projection(), vpDot2::searchDotsInArea(), vpRect::set(), vpRect::setBottomRight(), vpRect::setTopLeft(), vpDot2::track(), vpDot::track(), vpRect::vpRect(), vpTemplateTrackerTriangle::vpTemplateTrackerTriangle(), and vpCalibration::writeData().

double vpImagePoint::get_v ( ) const
inline

Gets the point coordinate corresponding to the $ v $ axes in the frame (u,v).

Returns
The value of the coordinate along the $ v $ axes.
See also
get_i(), get_j(), get_u()
Examples:
servoAfma4Point2DCamVelocityKalman.cpp, testConvert.cpp, trackDot.cpp, trackDot2.cpp, trackDot2WithAutoDetection.cpp, tutorial-detection-object-mbt2-deprecated.cpp, tutorial-detection-object-mbt2.cpp, tutorial-flood-fill.cpp, tutorial-klt-tracker-live-v4l2.cpp, and tutorial-klt-tracker.cpp.

Definition at line 274 of file vpImagePoint.h.

Referenced by vpCalibration::computeStdDeviation(), vpCalibration::computeStdDeviation_dist(), vpPixelMeterConversion::convertPoint(), vpDot2::defineDots(), vpDisplayGTK::displayCharString(), vpDisplayX::displayCharString(), vpDisplayOpenCV::displayCharString(), vpDisplayGTK::displayCircle(), vpDisplayX::displayCircle(), vpDisplayOpenCV::displayCircle(), vpCalibration::displayData(), vpDisplayGTK::displayDotLine(), vpDisplayX::displayDotLine(), vpDisplayX::displayImageROI(), vpDisplayGTK::displayLine(), vpDisplayX::displayLine(), vpDisplayOpenCV::displayLine(), vpDisplayGTK::displayPoint(), vpDisplayX::displayPoint(), vpDisplayOpenCV::displayPoint(), vpDisplayGTK::displayRectangle(), vpDisplayX::displayRectangle(), vpDisplayOpenCV::displayRectangle(), vpDisplayWin32::flushDisplayROI(), vpDisplayX::flushDisplayROI(), vpDot2::getDistance(), vpDot2::getFreemanChain(), vpTemplateTrackerTriangle::init(), vpImageSimulator::init(), vpPolygon::isInside(), vpRect::moveCenter(), vpHomography::project(), vpHomography::projection(), vpDot2::searchDotsInArea(), vpRect::set(), vpRect::setBottomRight(), vpRect::setTopLeft(), vpDot2::track(), vpDot::track(), vpRect::vpRect(), vpTemplateTrackerTriangle::vpTemplateTrackerTriangle(), and vpCalibration::writeData().

vpRect vpImagePoint::getBBox ( const std::vector< vpImagePoint > &  ipVec)
static

Computes and returns the bounding box.

Parameters
ipVec: Vector of input image points.
Returns
Bounding box of the points.

Definition at line 442 of file vpImagePoint.cpp.

bool vpImagePoint::inRectangle ( const vpRect rect) const

Check if an image point belongs to a rectangle.

Parameters
rect: the rectangle.
Returns
Returns true if the point belongs to the rectangle.

Definition at line 53 of file vpImagePoint.cpp.

References vpRect::getBottom(), vpRect::getLeft(), vpRect::getRight(), and vpRect::getTop().

Referenced by vpPlot::navigate().

vpImagePoint& vpImagePoint::operator*= ( const double  scale)
inline

Operator *=.

Definition at line 151 of file vpImagePoint.h.

vpImagePoint & vpImagePoint::operator+= ( const vpImagePoint ip)

Operator +=.

This operator can be used to compute the center of gravity of a set of image points.

#include <iostream>
#include <vector>
#include <visp3/core/vpImagePoint.h>
int main()
{
std::vector<vpImagePoint> ip(2);
ip[0].set_ij(100, 200);
ip[1].set_ij(300, 400);
vpImagePoint cog(0,0);
for(unsigned int i=0; i<ip.size(); i++)
cog += ip[i];
cog /= ip.size();
std::cout << "cog: " << cog << std::endl;
}

Definition at line 87 of file vpImagePoint.cpp.

vpImagePoint& vpImagePoint::operator-= ( const vpImagePoint ip)
inline

Operator -=.

Definition at line 140 of file vpImagePoint.h.

vpImagePoint & vpImagePoint::operator/= ( const double  scale)

Operator /=.

This operator can be used to compute the center of gravity of a set of image points.

#include <iostream>
#include <vector>
#include <visp3/core/vpImagePoint.h>
int main()
{
std::vector<vpImagePoint> ip(2);
ip[0].set_ij(100, 200);
ip[1].set_ij(300, 400);
vpImagePoint cog(0,0);
for(unsigned int i=0; i<ip.size(); i++)
cog += ip[i];
cog /= ip.size();
std::cout << "cog: " << cog << std::endl;
}

Definition at line 121 of file vpImagePoint.cpp.

vpImagePoint& vpImagePoint::operator= ( const vpImagePoint ip)
inline

Copy operator.

Definition at line 115 of file vpImagePoint.h.

vpImagePoint& vpImagePoint::operator= ( const vpImagePoint &&  ip)
inline

Move operator.

Definition at line 125 of file vpImagePoint.h.

void vpImagePoint::set_i ( const double  ii)
inline

Sets the point coordinate corresponding to the $ i $ axes in the frame (i,j).

Parameters
ii: The desired value for the coordinate along the $ i $ axes.
See also
set_j(), set_u(), set_v()
Examples:
AROgre.cpp, AROgreBasic.cpp, displayD3D.cpp, displayGTK.cpp, displayOpenCV.cpp, displayX.cpp, displayXMulti.cpp, manDisplay.cpp, servoAfma6Points2DCamVelocityEyeToHand.cpp, servoSimuFourPoints2DPolarCamVelocityDisplay.cpp, SickLDMRS-Process.cpp, testDisplays.cpp, testImagePoint.cpp, testTrackDot.cpp, and trackMeLine.cpp.

Definition at line 167 of file vpImagePoint.h.

Referenced by vpBSpline::computeCurveDers(), vpNurbs::computeCurveDersPoint(), vpNurbs::computeCurvePoint(), vpBSpline::computeCurvePoint(), vpMeLine::computeRhoTheta(), vpMeLine::display(), vpMeEllipse::display(), vpDisplayGTK::displayArrow(), vpDisplayX::displayArrow(), vpDisplayOpenCV::displayArrow(), vpDisplayGTK::displayCross(), vpDisplayX::displayCross(), vpDisplayOpenCV::displayCross(), vpMbtDistanceKltCylinder::displayPrimitive(), vpMbtDistanceKltPoints::displayPrimitive(), vpDisplayWin32::displayRectangle(), vpMeLine::getExtremities(), vpMeSite::getQueryList(), vpImage< double >::getValue(), vpImage< Type >::getValue(), vpImage< vpRGBa >::getValue(), vpMeTracker::initTracking(), vpMeEllipse::initTracking(), vpMeLine::intersection(), vpPolygon::isInside(), vpRectOriented::operator=(), vpMeEllipse::printParameters(), vpXmlParserRectOriented::readMainClass(), vpNurbs::refineKnotVectCurve(), vpNurbs::removeCurveKnot(), vpMeLine::sample(), vpMeLine::seekExtremities(), vpImageSimulator::setCameraPosition(), vpRectOriented::setOrientation(), vpRectOriented::setPoints(), vpRectOriented::setSize(), vpMeSite::track(), vpPolygon::updateCenter(), vpMeEllipse::vpMeEllipse(), vpRectOriented::vpRectOriented(), and vpMeEllipse::~vpMeEllipse().

void vpImagePoint::set_j ( const double  jj)
inline

Sets the point coordinate corresponding to the $ j $ axes in the frame (i,j).

Parameters
jj: The desired value for the coordinate along the $ j $ axes.
See also
set_i(), set_u(), set_v()
Examples:
AROgre.cpp, AROgreBasic.cpp, displayD3D.cpp, displayGTK.cpp, displayOpenCV.cpp, displayX.cpp, displayXMulti.cpp, manDisplay.cpp, servoAfma6Points2DCamVelocityEyeToHand.cpp, servoSimuFourPoints2DPolarCamVelocityDisplay.cpp, SickLDMRS-Process.cpp, testDisplays.cpp, testImagePoint.cpp, testTrackDot.cpp, and trackMeLine.cpp.

Definition at line 178 of file vpImagePoint.h.

Referenced by vpBSpline::computeCurveDers(), vpNurbs::computeCurveDersPoint(), vpNurbs::computeCurvePoint(), vpBSpline::computeCurvePoint(), vpMeLine::computeRhoTheta(), vpMeLine::display(), vpMeEllipse::display(), vpDisplayGTK::displayArrow(), vpDisplayX::displayArrow(), vpDisplayOpenCV::displayArrow(), vpDisplayGTK::displayCross(), vpDisplayX::displayCross(), vpDisplayOpenCV::displayCross(), vpMbtDistanceKltCylinder::displayPrimitive(), vpMbtDistanceKltPoints::displayPrimitive(), vpDisplayWin32::displayRectangle(), vp::findContours(), vpMeLine::getExtremities(), vpMeSite::getQueryList(), vpImage< double >::getValue(), vpImage< Type >::getValue(), vpImage< vpRGBa >::getValue(), vpMeTracker::initTracking(), vpMeEllipse::initTracking(), vpMeLine::intersection(), vpPolygon::isInside(), vpRectOriented::operator=(), vpMeEllipse::printParameters(), vpXmlParserRectOriented::readMainClass(), vpNurbs::removeCurveKnot(), vpMeLine::sample(), vpMeLine::seekExtremities(), vpImageSimulator::setCameraPosition(), vpRectOriented::setOrientation(), vpRectOriented::setPoints(), vpRectOriented::setSize(), vpMeSite::track(), vpPolygon::updateCenter(), vpMeEllipse::vpMeEllipse(), vpRectOriented::vpRectOriented(), and vpMeEllipse::~vpMeEllipse().

void vpImagePoint::set_uv ( const double  u,
const double  v 
)
inline

Sets the point coordinates in the frame (u,v).

Parameters
u: The desired value for the coordinate along the $ u $ axes.
v: The desired value for the coordinate along the $ v $ axes.
See also
set_i(), set_j(), set_u(), set_v()
Examples:
testKeyPoint-5.cpp, testKeyPoint-6.cpp, and tutorial-flood-fill.cpp.

Definition at line 248 of file vpImagePoint.h.

Referenced by vpDot2::defineDots(), vpTemplateTrackerZone::getCenter(), and vpTemplateTrackerTriangle::getCorners().

static double vpImagePoint::sqrDistance ( const vpImagePoint iP1,
const vpImagePoint iP2 
)
inlinestatic

Compute the distance $ |iP1 - iP2| = (i_1-i_2)^2+(j_1-j_2)^2 $

Parameters
iP1: First point
iP2: Second point
Returns
the distance between the two points.

Definition at line 301 of file vpImagePoint.h.

References get_i(), get_j(), operator*(), and vpMath::sqr().

Referenced by vpMeNurbs::localReSample(), and vpMeNurbs::sample().

Friends And Related Function Documentation

VISP_EXPORT bool operator!= ( const vpImagePoint ip1,
const vpImagePoint ip2 
)
friend

Returns true if ip1 and ip2 are different; otherwire returns true.

Definition at line 155 of file vpImagePoint.cpp.

VISP_EXPORT vpImagePoint operator* ( const vpImagePoint ip1,
const double  scale 
)
friend

Returns a vpImagePoint with coordinates multiplied by a scale factor.

#include <iostream>
#include <visp3/core/vpImagePoint.h>
int main()
{
vpImagePoint ip(100, 200); // Create an image point with coordinates i=100, j=200
std::cout << "ip: " << ip << std::endl; // coordinates (100, 200)
std::cout << "ip*2: " << ip*2 << std::endl; // new coordinates (200, 400)
return 0;
}

Definition at line 370 of file vpImagePoint.cpp.

VISP_EXPORT vpImagePoint operator+ ( const vpImagePoint ip1,
const vpImagePoint ip2 
)
friend

Returns a vpImagePoint wich is the sum of $ ip1 $ and $ ip2 $.

Definition at line 175 of file vpImagePoint.cpp.

VISP_EXPORT vpImagePoint operator+ ( const vpImagePoint ip1,
const int  offset 
)
friend

Returns a vpImagePoint with an offset added to the two coordinates.

#include <iostream>
#include <visp3/core/vpImagePoint.h>
int main()
{
vpImagePoint ip(100, 200); // Create an image point with coordinates i=100, j=200
std::cout << "ip: " << ip << std::endl; // coordinates (100, 200)
std::cout << "ip+10: " << ip+10 << std::endl; // new coordinates (110, 210)
return 0;
}

Definition at line 210 of file vpImagePoint.cpp.

VISP_EXPORT vpImagePoint operator+ ( const vpImagePoint ip1,
const unsigned int  offset 
)
friend

Returns a vpImagePoint with an offset added to the two coordinates.

#include <iostream>
#include <visp3/core/vpImagePoint.h>
int main()
{
vpImagePoint ip(100, 200); // Create an image point with coordinates i=100, j=200
std::cout << "ip: " << ip << std::endl; // coordinates (100, 200)
std::cout << "ip+10u: " << ip+10u << std::endl; // new coordinates (110, 210)
return 0;
}

Definition at line 235 of file vpImagePoint.cpp.

VISP_EXPORT vpImagePoint operator+ ( const vpImagePoint ip1,
const double  offset 
)
friend

Returns a vpImagePoint with an offset added to the two coordinates.

#include <iostream>
#include <visp3/core/vpImagePoint.h>
int main()
{
vpImagePoint ip(100, 200); // Create an image point with coordinates i=100, j=200
std::cout << "ip: " << ip << std::endl; // coordinates (100, 200)
std::cout << "ip+12.34: " << ip+12.34 << std::endl; // new coordinates (112.34, 212.34)
return 0;
}

Definition at line 260 of file vpImagePoint.cpp.

VISP_EXPORT vpImagePoint operator+= ( const vpImagePoint ip1,
const vpImagePoint ip2 
)
friend

Returns a vpImagePoint wich is the sum of $ ip1 $ and $ ip2 $.

Definition at line 186 of file vpImagePoint.cpp.

VISP_EXPORT vpImagePoint operator- ( const vpImagePoint ip1,
const vpImagePoint ip2 
)
friend

Returns a vpImagePoint wich is the difference between $ ip1 $ and $ ip2 $.

Definition at line 273 of file vpImagePoint.cpp.

VISP_EXPORT vpImagePoint operator- ( const vpImagePoint ip1,
const int  offset 
)
friend

Returns a vpImagePoint with an offset substracted to the two coordinates.

#include <iostream>
#include <visp3/core/vpImagePoint.h>
int main()
{
vpImagePoint ip(100, 200); // Create an image point with coordinates i=100, j=200
std::cout << "ip: " << ip << std::endl; // coordinates (100, 200)
std::cout << "ip-10: " << ip-10 << std::endl; // new coordinates (90, 190)
return 0;
}

Definition at line 297 of file vpImagePoint.cpp.

VISP_EXPORT vpImagePoint operator- ( const vpImagePoint ip1,
const unsigned int  offset 
)
friend

Returns a vpImagePoint with an offset substracted to the two coordinates.

#include <iostream>
#include <visp3/core/vpImagePoint.h>
int main()
{
vpImagePoint ip(100, 200); // Create an image point with coordinates i=100, j=200
std::cout << "ip: " << ip << std::endl; // coordinates (100, 200)
std::cout << "ip-10u: " << ip-10u << std::endl; // new coordinates (90, 190)
return 0;
}

Definition at line 321 of file vpImagePoint.cpp.

VISP_EXPORT vpImagePoint operator- ( const vpImagePoint ip1,
const double  offset 
)
friend

Returns a vpImagePoint with an offset substracted to the two coordinates.

#include <iostream>
#include <visp3/core/vpImagePoint.h>
int main()
{
vpImagePoint ip(100, 200); // Create an image point with coordinates i=100, j=200
std::cout << "ip: " << ip << std::endl; // coordinates (100, 200)
std::cout << "ip-12.34: " << ip-12.34 << std::endl; // new coordinates (87.66, 187.66)
return 0;
}

Definition at line 346 of file vpImagePoint.cpp.

VISP_EXPORT vpImagePoint operator/ ( const vpImagePoint ip1,
const double  scale 
)
friend

Returns a vpImagePoint with coordinates divided by a scale factor.

#include <iostream>
#include <visp3/core/vpImagePoint.h>
int main()
{
vpImagePoint ip(100, 200); // Create an image point with coordinates i=100, j=200
std::cout << "ip: " << ip << std::endl; // coordinates (100, 200)
std::cout << "ip/2: " << ip/2 << std::endl; // new coordinates (50, 100)
return 0;
}

Definition at line 394 of file vpImagePoint.cpp.

VISP_EXPORT std::ostream & operator<< ( std::ostream &  os,
const vpImagePoint ip 
)
friend

Writes the image point coordinates ip to the stream os, and returns a reference to the stream. Writes the first coordinate along the i axis and then the second one along the j axis. The coordinates are separated by a comma.

The following code

#include <iostream>
#include <visp3/core/vpImagePoint.h>
int main()
{
ip.set_i(10);
ip.set_j(11.1);
std::cout << "Image point with coordinates: " << ip << std::endl;
return 0;
}

produces the output:

Image point with coordinates: 10, 11.1

Definition at line 431 of file vpImagePoint.cpp.

VISP_EXPORT bool operator== ( const vpImagePoint ip1,
const vpImagePoint ip2 
)
friend

Returns true if ip1 and ip2 are equal; otherwire returns false.

Definition at line 134 of file vpImagePoint.cpp.