Visual Servoing Platform  version 3.4.0
vpArray2D< Type > Class Template Reference

#include <vpArray2D.h>

Public Member Functions

 vpArray2D ()
 
 vpArray2D (const vpArray2D< Type > &A)
 
 vpArray2D (unsigned int r, unsigned int c)
 
 vpArray2D (unsigned int r, unsigned int c, Type val)
 
 vpArray2D (vpArray2D< Type > &&A) noexcept
 
 vpArray2D (const std::initializer_list< Type > &list)
 
 vpArray2D (unsigned int nrows, unsigned int ncols, const std::initializer_list< Type > &list)
 
 vpArray2D (const std::initializer_list< std::initializer_list< Type > > &lists)
 
virtual ~vpArray2D ()
 
template<>
bool operator== (const vpArray2D< float > &A) const
 

Static Public Member Functions

Inherited I/O from vpArray2D with Static Public Member Functions
static bool load (const std::string &filename, vpArray2D< Type > &A, bool binary=false, char *header=NULL)
 
static bool loadYAML (const std::string &filename, vpArray2D< Type > &A, char *header=NULL)
 
static bool save (const std::string &filename, const vpArray2D< Type > &A, bool binary=false, const char *header="")
 
static bool saveYAML (const std::string &filename, const vpArray2D< Type > &A, const char *header="")
 

Public Attributes

Type * data
 

Protected Attributes

unsigned int rowNum
 
unsigned int colNum
 
Type ** rowPtrs
 
unsigned int dsize
 

Related Functions

(Note that these are not member functions.)

enum  vpGEMMmethod
 
template<>
bool operator== (const vpArray2D< double > &A) const
 
void vpGEMM (const vpArray2D< double > &A, const vpArray2D< double > &B, const double &alpha, const vpArray2D< double > &C, const double &beta, vpArray2D< double > &D, const unsigned int &ops=0)
 

Inherited functionalities from vpArray2D

std::ostream & operator<< (std::ostream &s, const vpArray2D< Type > &A)
 
unsigned int getCols () const
 
Type getMaxValue () const
 
Type getMinValue () const
 
unsigned int getRows () const
 
unsigned int size () const
 
void resize (unsigned int nrows, unsigned int ncols, bool flagNullify=true, bool recopy_=true)
 
void reshape (unsigned int nrows, unsigned int ncols)
 
bool operator== (const vpArray2D< Type > &A) const
 
bool operator!= (const vpArray2D< Type > &A) const
 
vpArray2D< Type > & operator= (Type x)
 
vpArray2D< Type > & operator= (const vpArray2D< Type > &A)
 
vpArray2D< Type > & operator= (vpArray2D< Type > &&other) noexcept
 
vpArray2D< Type > & operator= (const std::initializer_list< Type > &list)
 
vpArray2D< Type > & operator= (const std::initializer_list< std::initializer_list< Type > > &lists)
 
Type * operator[] (unsigned int i)
 
Type * operator[] (unsigned int i) const
 
vpArray2D< Type > hadamard (const vpArray2D< Type > &m) const
 

Detailed Description

template<class Type>
class vpArray2D< Type >

Implementation of a generic 2D array used as base class for matrices and vectors.

This class implements a 2D array as a template class and all the basic functionalities common to matrices and vectors. More precisely:

The code below shows how to create a 2-by-3 array of doubles, set the element values and access them:

#include <visp3/code/vpArray2D.h
int main()
{
vpArray2D<float> a(2, 3);
a[0][0] = -1; a[0][1] = -2; a[0][2] = -3;
a[1][0] = 4; a[1][1] = 5.5; a[1][2] = 6;
std::cout << "a:" << std::endl;
for (unsigned int i = 0; i < a.getRows(); i++) {
for (unsigned int j = 0; j < a.getCols(); j++) {
std::cout << a[i][j] << " ";
}
std::cout << std::endl;
}
}

Once build, this previous code produces the following output:

a:
-1 -2 -3
4 5.5 6

If ViSP is build with c++11 enabled, you can do the same using:

#include <visp3/code/vpArray2D.h
int main()
{
#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
vpArray2D<float> a{ {-1, -2, -3}, {4, 5.5, 6.0f} };
std::cout << "a:\n" << a << std::endl;
#endif
}

The array could also be initialized using operator=(const std::initializer_list< std::initializer_list< Type > > &)

int main()
{
#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
a = { {-1, -2, -3}, {4, 5.5, 6.0f} };
#endif
}

You can also use reshape() function:

#include <visp3/code/vpArray2D.h
int main()
{
#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
vpArray2D<float> a{ -1, -2, -3, 4, 5.5, 6.0f };
a.reshape(2, 3);
#endif
}
Examples:
testArray2D.cpp, testMatrixInitialization.cpp, testRealSense2_T265_undistort.cpp, testUndistortImage.cpp, and tutorial-apriltag-detector-live-T265-realsense.cpp.

Definition at line 131 of file vpArray2D.h.

Constructor & Destructor Documentation

template<class Type>
vpArray2D< Type >::vpArray2D ( )
inline

Basic constructor of a 2D array. Number of columns and rows are set to zero.

Definition at line 152 of file vpArray2D.h.

template<class Type>
vpArray2D< Type >::vpArray2D ( const vpArray2D< Type > &  A)
inline

Copy constructor of a 2D array.

Definition at line 157 of file vpArray2D.h.

template<class Type>
vpArray2D< Type >::vpArray2D ( unsigned int  r,
unsigned int  c 
)
inline

Constructor that initializes a 2D array with 0.

Parameters
r: Array number of rows.
c: Array number of columns.

Definition at line 174 of file vpArray2D.h.

template<class Type>
vpArray2D< Type >::vpArray2D ( unsigned int  r,
unsigned int  c,
Type  val 
)
inline

Constructor that initialize a 2D array with val.

Parameters
r: Array number of rows.
c: Array number of columns.
val: Each element of the array is set to val.

Definition at line 191 of file vpArray2D.h.

template<class Type>
vpArray2D< Type >::vpArray2D ( vpArray2D< Type > &&  A)
inlinenoexcept

Definition at line 203 of file vpArray2D.h.

template<class Type>
vpArray2D< Type >::vpArray2D ( const std::initializer_list< Type > &  list)
inlineexplicit

Definition at line 218 of file vpArray2D.h.

template<class Type>
vpArray2D< Type >::vpArray2D ( unsigned int  nrows,
unsigned int  ncols,
const std::initializer_list< Type > &  list 
)
inlineexplicit

Definition at line 224 of file vpArray2D.h.

template<class Type>
vpArray2D< Type >::vpArray2D ( const std::initializer_list< std::initializer_list< Type > > &  lists)
inlineexplicit

Definition at line 238 of file vpArray2D.h.

template<class Type>
virtual vpArray2D< Type >::~vpArray2D ( )
inlinevirtual

Destructor that desallocate memory.

Definition at line 258 of file vpArray2D.h.

Member Function Documentation

template<class Type>
unsigned int vpArray2D< Type >::getCols ( ) const
inline

Return the number of columns of the 2D array.

See also
getRows(), size()

Definition at line 279 of file vpArray2D.h.

Referenced by vpMatrix::add2Matrices(), vpMatrix::add2WeightedMatrices(), vpRotationMatrix::buildFrom(), vpQuadProg::checkDimensions(), vpSubRowVector::checkParentStatus(), vpSubMatrix::checkParentStatus(), vpLinProg::colReduction(), vpServo::computeControlLaw(), vpMatrix::computeCovarianceMatrix(), vpMatrix::computeHLM(), vpServo::computeInteractionMatrix(), vpMbTracker::computeJTR(), vpServo::computeProjectionOperators(), vpMbGenericTracker::computeVVS(), vpMbTracker::computeVVSPoseEstimation(), vpMatrix::conv2(), vpMatrix::expm(), vpImageFilter::filter(), vpQuadProg::fromCanonicalCost(), vpImageSimulator::getImage(), vpImageFilter::getSobelKernelX(), vpImageFilter::getSobelKernelY(), vpColVector::hadamard(), vpMatrix::hadamard(), vpArray2D< Type >::hadamard(), vpSubRowVector::init(), vpSubMatrix::init(), vpRowVector::init(), vpMatrix::init(), vpTemplateTrackerSSDInverseCompositional::initCompInverse(), vpCameraParameters::initFromCalibrationMatrix(), vpRowVector::insert(), vpMatrix::insert(), vpMatrix::inverseByCholeskyLapack(), vpMatrix::juxtaposeMatrices(), vpMatrix::kron(), vpRowVector::mean(), vpMatrix::mult2Matrices(), vpMatrix::multMatrixVector(), vpTranslationVector::operator*(), vpRotationMatrix::operator*(), vpForceTwistMatrix::operator*(), vpVelocityTwistMatrix::operator*(), vpRowVector::operator*(), vpColVector::operator*(), vpMatrix::operator*(), vpRowVector::operator+(), vpRowVector::operator+=(), vpMatrix::operator+=(), vpRowVector::operator-(), vpRowVector::operator-=(), vpMatrix::operator-=(), vpSubRowVector::operator=(), vpSubColVector::operator=(), vpSubMatrix::operator=(), vpRotationMatrix::operator=(), vpRowVector::operator=(), vpColVector::operator=(), vpHomography::operator=(), vpMatrix::operator=(), vpMatrix::printSize(), vpIoTools::readConfigVar(), vpRowVector::reshape(), vpColVector::reshape(), vpLinProg::rowReduction(), vpArray2D< double >::save(), vpArray2D< double >::saveYAML(), vpServo::secondaryTask(), vpServo::secondaryTaskJointLimitAvoidance(), vpServo::setInteractionMatrixType(), vpQuadProg::solveByProjection(), vpLinProg::solveLP(), vpQuadProg::solveQP(), vpQuadProg::solveQPe(), vpQuadProg::solveQPi(), vpQuadProg::solveSVDorQR(), vpRowVector::stack(), vpMatrix::stack(), vpMatrix::stackRows(), vpMatrix::sub2Matrices(), vpMatrix::svdEigen3(), vpMbGenericTracker::track(), vp::visp2eigen(), vpColVector::vpColVector(), vpRowVector::vpRowVector(), and vpImageTools::warpImage().

template<class Type >
Type vpArray2D< Type >::getMaxValue ( ) const

Return the array max value.

Definition at line 912 of file vpArray2D.h.

References vpArray2D< Type >::data.

Referenced by vpArray2D< double >::getCols().

template<class Type >
Type vpArray2D< Type >::getMinValue ( ) const

Return the array min value.

Definition at line 895 of file vpArray2D.h.

References vpArray2D< Type >::data.

Referenced by vpArray2D< double >::getCols().

template<class Type>
unsigned int vpArray2D< Type >::getRows ( ) const
inline

Return the number of rows of the 2D array.

See also
getCols(), size()

Definition at line 289 of file vpArray2D.h.

Referenced by vpMatrix::add2Matrices(), vpMatrix::add2WeightedMatrices(), vpLinProg::allClose(), vpLinProg::allGreater(), vpLinProg::allLesser(), vpLinProg::allZero(), vpRotationMatrix::buildFrom(), vpQuadProg::checkDimensions(), vpSubColVector::checkParentStatus(), vpSubMatrix::checkParentStatus(), vpLinProg::colReduction(), vpServo::computeControlLaw(), vpMatrix::computeCovarianceMatrix(), vpMatrix::computeCovarianceMatrixVVS(), vpServo::computeError(), vpMatrix::computeHLM(), vpServo::computeInteractionMatrix(), vpMbTracker::computeJTR(), vpPtu46::computeMGD(), vpPoseFeatures::computePose(), vpMbDepthDenseTracker::computeVVS(), vpMbDepthNormalTracker::computeVVS(), vpMbEdgeKltTracker::computeVVS(), vpMbKltTracker::computeVVS(), vpMbGenericTracker::computeVVS(), vpMbEdgeTracker::computeVVS(), vpMbTracker::computeVVSCheckLevenbergMarquardt(), vpMbEdgeTracker::computeVVSFirstPhasePoseEstimation(), vpMbDepthDenseTracker::computeVVSInteractionMatrixAndResidu(), vpMbTracker::computeVVSPoseEstimation(), vpMbEdgeTracker::computeVVSWeights(), vpMbTracker::computeVVSWeights(), vpMatrix::conv2(), vpMatrix::createDiagonalMatrix(), vpColVector::crossProd(), vpDot2::defineDots(), vpMatrix::diag(), vpProjectionDisplay::display(), vpColVector::dotProd(), vpGenericFeature::error(), vpMatrix::expm(), vpImageFilter::filter(), vpQuadProg::fromCanonicalCost(), vpPtu46::get_eJe(), vpBiclops::get_eJe(), vpPtu46::get_fJe(), vpBiclops::get_fJe(), vpBiclops::get_fMe(), vpGenericFeature::get_s(), vpBasicFeature::getDimension(), vpImageSimulator::getImage(), vpAfma6::getInverseKinematics(), vpViper::getInverseKinematicsWrist(), vpImageFilter::getSobelKernelX(), vpImageFilter::getSobelKernelY(), vpColVector::hadamard(), vpMatrix::hadamard(), vpArray2D< Type >::hadamard(), vpSubColVector::init(), vpSubMatrix::init(), vpColVector::init(), vpMatrix::init(), vpTemplateTrackerSSDInverseCompositional::initCompInverse(), vpCameraParameters::initFromCalibrationMatrix(), vpMatrix::insert(), vpFeatureLuminance::interaction(), vpGenericFeature::interaction(), vpMatrix::inverseByCholeskyLapack(), vpMatrix::inverseByQRLapack(), vpColVector::invSort(), vpMatrix::juxtaposeMatrices(), vpMatrix::kernel(), vpScale::KernelDensity(), vpScale::KernelDensityGradient(), vpMatrix::kron(), vpColVector::mean(), vpScale::MeanShift(), vpRobust::MEstimator(), vpMatrix::mult2Matrices(), vpMatrix::multMatrixVector(), vpRotationMatrix::operator*(), vpForceTwistMatrix::operator*(), vpVelocityTwistMatrix::operator*(), vpHomogeneousMatrix::operator*(), vpRowVector::operator*(), vpMatrix::operator*(), vpColVector::operator+(), vpColVector::operator+=(), vpMatrix::operator+=(), vpColVector::operator-(), vpColVector::operator-=(), vpMatrix::operator-=(), vpSubColVector::operator=(), vpSubRowVector::operator=(), vpSubMatrix::operator=(), vpRGBa::operator=(), vpRotationMatrix::operator=(), vpRowVector::operator=(), vpColVector::operator=(), vpHomography::operator=(), vpMatrix::operator=(), vpPlot::plot(), vpPose::poseVirtualVSrobust(), vpKalmanFilter::prediction(), vpMatrix::printSize(), vpLine::projection(), vpIoTools::readConfigVar(), vpRowVector::reshape(), vpColVector::reshape(), vpLinProg::rowReduction(), vpArray2D< double >::save(), vpArray2D< double >::saveYAML(), vpGenericFeature::set_s(), vpQuadProg::setEqualityConstraint(), vpGenericFeature::setError(), vpMbTracker::setEstimatedDoF(), vpGenericFeature::setInteractionMatrix(), vpServo::setInteractionMatrixType(), vpSimulatorAfma6::setJointLimit(), vpSimulatorViper850::setJointLimit(), vpRobotAfma4::setPosition(), vpRobotBiclops::setVelocity(), vpRobotPtu46::setVelocity(), vpSimulatorAfma6::setVelocity(), vpSimulatorViper850::setVelocity(), vpRobotAfma4::setVelocity(), vpLine::setWorldCoordinates(), vpLinProg::simplex(), vpRobust::simultMEstimator(), vpColVector::skew(), vpQuadProg::solveByProjection(), vpLinProg::solveLP(), vpQuadProg::solveQP(), vpQuadProg::solveQPe(), vpQuadProg::solveQPi(), vpQuadProg::solveSVDorQR(), vpColVector::sort(), vpColVector::stack(), vpMatrix::stack(), vpMatrix::stackRows(), vpMatrix::sub2Matrices(), vpMatrix::svdEigen3(), vpMbGenericTracker::track(), vp::visp2eigen(), vpColVector::vpColVector(), vpRowVector::vpRowVector(), vpImageTools::warpImage(), and vpImageTools::warpLinear().

template<class Type>
vpArray2D< Type > vpArray2D< Type >::hadamard ( const vpArray2D< Type > &  m) const

Compute the Hadamard product (element wise matrix multiplication).

Parameters
m: Second matrix;
Returns
m1.hadamard(m2) The Hadamard product : $ m1 \circ m2 = (m1 \circ m2)_{i,j} = (m1)_{i,j} (m2)_{i,j} $

Definition at line 932 of file vpArray2D.h.

References vpArray2D< Type >::colNum, vpArray2D< Type >::data, vpException::dimensionError, vpArray2D< Type >::dsize, vpArray2D< Type >::getCols(), vpArray2D< Type >::getRows(), and vpArray2D< Type >::resize().

Referenced by vpColVector::extract(), and vpMatrix::setLapackMatrixMinSize().

template<class Type>
static bool vpArray2D< Type >::load ( const std::string &  filename,
vpArray2D< Type > &  A,
bool  binary = false,
char *  header = NULL 
)
inlinestatic

Load a matrix from a file.

Parameters
filename: Absolute file name.
A: Array to be loaded
binary: If true the matrix is loaded from a binary file, else from a text file.
header: Header of the file is loaded in this parameter.
Returns
Returns true if success.
See also
save()

Definition at line 540 of file vpArray2D.h.

Referenced by vpMatrix::loadMatrix(), vpHomogeneousMatrix::~vpHomogeneousMatrix(), vpHomography::~vpHomography(), and vpPoseVector::~vpPoseVector().

template<class Type>
static bool vpArray2D< Type >::loadYAML ( const std::string &  filename,
vpArray2D< Type > &  A,
char *  header = NULL 
)
inlinestatic

Load an array from a YAML-formatted file.

Parameters
filename: absolute file name.
A: array to be loaded from the file.
header: header of the file is loaded in this parameter.
Returns
Returns true on success.
See also
saveYAML()

Definition at line 652 of file vpArray2D.h.

Referenced by vpMatrix::loadMatrixYAML().

template<class Type>
bool vpArray2D< Type >::operator!= ( const vpArray2D< Type > &  A) const

Not equal to comparison operator of a 2D array.

Definition at line 996 of file vpArray2D.h.

Referenced by vpRowVector::operator[](), vpColVector::operator[](), and vpArray2D< double >::reshape().

template<class Type>
vpArray2D<Type>& vpArray2D< Type >::operator= ( const vpArray2D< Type > &  A)
inline

Copy operator of a 2D array.

Definition at line 422 of file vpArray2D.h.

template<class Type>
vpArray2D<Type>& vpArray2D< Type >::operator= ( vpArray2D< Type > &&  other)
inlinenoexcept

Definition at line 432 of file vpArray2D.h.

template<class Type>
vpArray2D<Type>& vpArray2D< Type >::operator= ( const std::initializer_list< Type > &  list)
inline

Definition at line 454 of file vpArray2D.h.

template<class Type>
vpArray2D<Type>& vpArray2D< Type >::operator= ( const std::initializer_list< std::initializer_list< Type > > &  lists)
inline

Definition at line 464 of file vpArray2D.h.

template<class Type>
bool vpArray2D< Type >::operator== ( const vpArray2D< Type > &  A) const
template<>
bool vpArray2D< float >::operator== ( const vpArray2D< float > &  A) const
inline
template<class Type>
Type* vpArray2D< Type >::operator[] ( unsigned int  i)
inline

Set element $A_{ij} = x$ using A[i][j] = x.

Definition at line 484 of file vpArray2D.h.

template<class Type>
Type* vpArray2D< Type >::operator[] ( unsigned int  i) const
inline

Get element $x = A_{ij}$ using x = A[i][j].

Definition at line 486 of file vpArray2D.h.

template<class Type>
void vpArray2D< Type >::reshape ( unsigned int  nrows,
unsigned int  ncols 
)
inline
Examples:
testMatrixInitialization.cpp.

Definition at line 379 of file vpArray2D.h.

Referenced by vpRowVector::rad2deg(), and vpColVector::rad2deg().

template<class Type>
void vpArray2D< Type >::resize ( unsigned int  nrows,
unsigned int  ncols,
bool  flagNullify = true,
bool  recopy_ = true 
)
inline

Set the size of the array and initialize all the values to zero.

Parameters
nrows: number of rows.
ncols: number of column.
flagNullify: if true, then the array is re-initialized to 0 after resize. If false, the initial values from the common part of the array (common part between old and new version of the array) are kept. Default value is true.
recopy_: if true, will perform an explicit recopy of the old data.

Definition at line 304 of file vpArray2D.h.

Referenced by vpMatrix::AAt(), vpMatrix::add2Matrices(), vpMatrix::add2WeightedMatrices(), vpMatrix::AtA(), vpLinProg::colReduction(), vpMbtFaceDepthNormal::computeInteractionMatrix(), vpMbtFaceDepthDense::computeInteractionMatrixAndResidu(), vpPoseFeatures::computePose(), vpServo::computeProjectionOperators(), vpMbEdgeKltTracker::computeVVS(), vpMbDepthDenseTracker::computeVVSInit(), vpMbDepthNormalTracker::computeVVSInit(), vpMbKltTracker::computeVVSInit(), vpMbGenericTracker::computeVVSInit(), vpMbEdgeTracker::computeVVSInit(), vpMatrix::cond(), vpMatrix::conv2(), vpMatrix::createDiagonalMatrix(), vpProjectionDisplay::display(), vpHomography::DLT(), vp::eigen2visp(), vpMatrix::eigenValues(), vpMatrix::expm(), vpMatrix::extract(), vpPtu46::get_eJe(), vpRobotFlirPtu::get_eJe(), vpAfma4::get_eJe(), vpAfma6::get_eJe(), vpBiclops::get_eJe(), vpRobotFranka::get_eJe(), vpPtu46::get_fJe(), vpRobotFlirPtu::get_fJe(), vpAfma4::get_fJe(), vpAfma6::get_fJe(), vpBiclops::get_fJe(), vpRobotFranka::get_fJe(), vpAfma4::get_fJe_inverse(), vpViper::get_fJw(), vpRobotFranka::getMass(), vpMatrix::hadamard(), vpArray2D< Type >::hadamard(), vpProjectionDisplay::init(), vpKalmanFilter::init(), vpTemplateTrackerMIESM::initCompInverse(), vpMbtDistanceCircle::initInteractionMatrixError(), vpMbtDistanceCylinder::initInteractionMatrixError(), vpTemplateTracker::initTracking(), vpImageTools::initUndistortMap(), vpMatrix::insert(), vpFeatureVanishingPoint::interaction(), vpFeatureLuminance::interaction(), vpFeatureEllipse::interaction(), vpFeatureSegment::interaction(), vpFeatureDepth::interaction(), vpGenericFeature::interaction(), vpFeaturePoint::interaction(), vpFeaturePoint3D::interaction(), vpFeatureThetaU::interaction(), vpFeaturePointPolar::interaction(), vpFeatureTranslation::interaction(), vpMatrix::inverseByLU(), vpMatrix::inverseByQRLapack(), vpMatrix::inverseTriangular(), vpMatrix::juxtaposeMatrices(), vpMatrix::kernel(), vpMatrix::kron(), vpArray2D< double >::load(), vpArray2D< double >::loadYAML(), vpMatrix::mult2Matrices(), vpMatrix::negateMatrix(), vpMatrix::nullSpace(), vpMatrix::operator*(), vpMatrix::operator/(), vpRotationVector::operator=(), vpArray2D< double >::operator=(), vpPose::poseVirtualVSrobust(), vpMatrix::pseudoInverse(), vpMatrix::qr(), vpMatrix::qrPivot(), vpIoTools::readConfigVar(), vpRowVector::reshape(), vpColVector::reshape(), vpArray2D< double >::reshape(), vpRowVector::resize(), vpColVector::resize(), vpLinProg::rowReduction(), vpServo::secondaryTask(), vpServo::setInteractionMatrixType(), vpMbTracker::setProjectionErrorKernelSize(), vpTranslationVector::skew(), vpColVector::skew(), vpLinProg::solveLP(), vpQuadProg::solveQPi(), vpMatrix::stack(), vpMatrix::sub2Matrices(), vpMatrix::svdEigen3(), vpMatrix::svdLapack(), vpMatrix::svdOpenCV(), vpMbGenericTracker::track(), vpMatrix::transpose(), vpArray2D< double >::vpArray2D(), vpTemplateTrackerMI::vpTemplateTrackerMI(), vpTemplateTrackerSSD::vpTemplateTrackerSSD(), vpTemplateTrackerSSDESM::vpTemplateTrackerSSDESM(), vpTemplateTrackerSSDInverseCompositional::vpTemplateTrackerSSDInverseCompositional(), vpTemplateTrackerWarpHomographySL3::vpTemplateTrackerWarpHomographySL3(), and vpTemplateTrackerZNCC::vpTemplateTrackerZNCC().

template<class Type>
static bool vpArray2D< Type >::save ( const std::string &  filename,
const vpArray2D< Type > &  A,
bool  binary = false,
const char *  header = "" 
)
inlinestatic

Save a matrix to a file.

Parameters
filename: Absolute file name.
A: Array to be saved.
binary: If true the matrix is saved in a binary file, else a text file.
header: Optional line that will be saved at the beginning of the file.
Returns
Returns true if success.

Warning : If you save the matrix as in a text file the precision is less than if you save it in a binary file.

See also
load()

Definition at line 737 of file vpArray2D.h.

Referenced by vpPoseVector::resize(), vpHomography::resize(), vpMatrix::saveMatrix(), and vpHomogeneousMatrix::~vpHomogeneousMatrix().

template<class Type>
static bool vpArray2D< Type >::saveYAML ( const std::string &  filename,
const vpArray2D< Type > &  A,
const char *  header = "" 
)
inlinestatic

Save an array in a YAML-formatted file.

Parameters
filename: absolute file name.
A: array to be saved in the file.
header: optional lines that will be saved at the beginning of the file. Should be YAML-formatted and will adapt to the indentation if any.
Returns
Returns true if success.

Here is an example of outputs.

vpArray2D::saveYAML("matrix.yml", M, "example: a YAML-formatted header");
vpArray2D::saveYAML("matrixIndent.yml", M, "example:\n - a YAML-formatted
header\n - with inner indentation");

Content of matrix.yml:

example: a YAML-formatted header
rows: 3
cols: 4
- [0, 0, 0, 0]
- [0, 0, 0, 0]
- [0, 0, 0, 0]

Content of matrixIndent.yml:

example:
- a YAML-formatted header
- with inner indentation
rows: 3
cols: 4
- [0, 0, 0, 0]
- [0, 0, 0, 0]
- [0, 0, 0, 0]
See also
loadYAML()

Definition at line 830 of file vpArray2D.h.

Referenced by vpMatrix::saveMatrixYAML().

template<class Type>
unsigned int vpArray2D< Type >::size ( ) const
inline

Return the number of elements of the 2D array.

Definition at line 291 of file vpArray2D.h.

Referenced by vpVirtuose::addForce(), vpForceTorqueAtiSensor::bias(), vpQuaternionVector::buildFrom(), vpTranslationVector::buildFrom(), vpRxyzVector::buildFrom(), vpRzyzVector::buildFrom(), vpRzyxVector::buildFrom(), vpThetaUVector::buildFrom(), vpMbtFaceDepthNormal::computeNormalVisibility(), vpExponentialMap::direct(), vpColVector::dotProd(), vpMbtFaceDepthNormal::estimatePlaneEquationSVD(), vpRobotFranka::get_fJe(), vpRobotFranka::get_fMe(), vpForceTorqueAtiSensor::getForceTorque(), vpPoint::getWorldCoordinates(), vpMatrix::inducedL2Norm(), vpRowVector::insert(), vpColVector::insert(), vpMatrix::insert(), vpRowVector::mean(), vpColVector::mean(), vpRowVector::median(), vpColVector::median(), vpHomography::operator*(), vpColVector::operator*(), vpTranslationVector::operator+(), vpRotationVector::operator=(), vpQuaternionVector::operator=(), vpTranslationVector::operator=(), vpRxyzVector::operator=(), vpRzyzVector::operator=(), vpRzyxVector::operator=(), vpThetaUVector::operator=(), vpArray2D< Type >::operator==(), vpPlot::plot(), vpMatrix::pseudoInverse(), vpRobot::saturateVelocities(), vpServo::secondaryTaskJointLimitAvoidance(), vpImageFilter::sepFilter(), vpVirtuose::setArticularForce(), vpVirtuose::setArticularPosition(), vpVirtuose::setArticularVelocity(), vpServo::setCameraDoF(), vpRobotTemplate::setCartVelocity(), vpRobotFlirPtu::setCartVelocity(), vpRobotKinova::setCartVelocity(), vpVirtuose::setForce(), vpRobotFranka::setForceTorque(), vpRobotKinova::setJointVelocity(), vpRobotFlirPtu::setPanPosLimits(), vpQbSoftHand::setPosition(), vpReflexTakktile2::setPosition(), vpRobotKinova::setPosition(), vpRobotFlirPtu::setPosition(), vpReflexTakktile2::setPositioningVelocity(), vpRobotFlirPtu::setTiltPosLimits(), vpRobotTemplate::setVelocity(), vpRobotBebop2::setVelocity(), vpSimulatorPioneer::setVelocity(), vpRobotPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpRobotKinova::setVelocity(), vpRobotFlirPtu::setVelocity(), vpVirtuose::setVelocity(), vpRobotFranka::setVelocity(), vpReflexTakktile2::setVelocityUntilAnyContact(), vpReflexTakktile2::setVelocityUntilEachContact(), vpPoint::setWorldCoordinates(), vpQuadProg::solveQPi(), vpMatrix::stack(), vpRowVector::stdev(), vpColVector::stdev(), vpMatrix::svdEigen3(), vpForceTorqueAtiSensor::unbias(), vp::visp2eigen(), vpArray2D< double >::vpArray2D(), vpColVector::vpColVector(), vpTranslationVector::vpTranslationVector(), and vpTemplateTrackerWarp::warpTriangle().

Friends And Related Function Documentation

template<class Type>
std::ostream& operator<< ( std::ostream &  s,
const vpArray2D< Type > &  A 
)
friend
bool operator== ( const vpArray2D< double > &  A) const
related
template<class Type>
void vpGEMM ( const vpArray2D< double > &  A,
const vpArray2D< double > &  B,
const double &  alpha,
const vpArray2D< double > &  C,
const double &  beta,
vpArray2D< double > &  D,
const unsigned int &  ops = 0 
)
related

This function performs generalized matrix multiplication: D = alpha*op(A)*op(B) + beta*op(C), where op(X) is X or X^T. Operation on A, B and C matrices is described by enumeration vpGEMMmethod().

For example, to compute D = alpha*A^T*B^T+beta*C we need to call :

vpGEMM(A, B, alpha, C, beta, D, VP_GEMM_A_T + VP_GEMM_B_T);

If C is not used, vpGEMM must be called using an empty array null. Thus to compute D = alpha*A^T*B, we have to call:

vpGEMM(A, B, alpha, null, 0, D, VP_GEMM_B_T);
Exceptions
vpException::incorrectMatrixSizeErrorif the sizes of the matrices do not allow the operations.
Parameters
A: An array that could be a vpMatrix.
B: An array that could be a vpMatrix.
alpha: A scalar.
C: An array that could be a vpMatrix.
beta: A scalar.
D: The resulting array that could be a vpMatrix.
ops: A scalar describing operation applied on the matrices. Possible values are the one defined in vpGEMMmethod(): VP_GEMM_A_T, VP_GEMM_B_T, VP_GEMM_C_T.
Examples:
testMatrix.cpp.

Definition at line 393 of file vpGEMM.h.

References vpException::functionNotImplementedError.

template<class Type>
enum vpGEMMmethod
related

Enumeration of the operations applied on matrices in vpGEMM() function.

Operations are :

  • VP_GEMM_A_T to use the transpose matrix of A instead of the matrix A
  • VP_GEMM_B_T to use the transpose matrix of B instead of the matrix B
  • VP_GEMM_C_T to use the transpose matrix of C instead of the matrix C

Definition at line 57 of file vpGEMM.h.

Member Data Documentation

template<class Type>
Type* vpArray2D< Type >::data

Address of the first element of the data array.

Definition at line 145 of file vpArray2D.h.

Referenced by vpMatrix::AAt(), vpMatrix::AtA(), vpMbtFaceDepthDense::computeInteractionMatrixAndResidu(), vpMbTracker::computeJTR(), vpMatrix::conv2(), vpMatrix::detByLULapack(), vpColVector::dotProd(), vp::eigen2visp(), vpMatrix::eigenValues(), vpMatrix::expm(), vpRobotViper650::getForceTorque(), vpRobotViper850::getForceTorque(), vpArray2D< Type >::getMaxValue(), vpArray2D< Type >::getMinValue(), vpRobotViper650::getPosition(), vpRobotViper850::getPosition(), vpMatrix::getRow(), vpImageFilter::getSobelKernelX(), vpImageFilter::getSobelKernelY(), vpRobotViper650::getVelocity(), vpRobotViper850::getVelocity(), vpColVector::hadamard(), vpMatrix::hadamard(), vpArray2D< Type >::hadamard(), vpSubColVector::init(), vpSubRowVector::init(), vpSubMatrix::init(), vpRobotViper650::init(), vpRobotViper850::init(), vpTemplateTrackerMIESM::initHessienDesired(), vpColVector::insert(), vpMatrix::insert(), vpMatrix::inverseByCholeskyLapack(), vpMatrix::inverseByCholeskyOpenCV(), vpMatrix::inverseByLUEigen3(), vpMatrix::inverseByLULapack(), vpMatrix::inverseByLUOpenCV(), vpMatrix::inverseByQRLapack(), vpMatrix::inverseTriangular(), vpColVector::invSort(), vpRowVector::mean(), vpColVector::mean(), vpRowVector::median(), vpColVector::median(), vpRobust::MEstimator(), vpMatrix::mult2Matrices(), vpMatrix::multMatrixVector(), vpTranslationVector::operator*(), vpRowVector::operator*(), vpHomography::operator*(), vpColVector::operator*(), vpMatrix::operator*(), vpTranslationVector::operator-(), vpRowVector::operator-(), vpColVector::operator-(), vpTranslationVector::operator/(), vpRowVector::operator/(), vpHomography::operator/(), vpColVector::operator/(), vpSubColVector::operator=(), vpRotationVector::operator=(), vpTranslationVector::operator=(), vpRowVector::operator=(), vpColVector::operator=(), vpMatrix::operator=(), vpArray2D< double >::operator=(), vpRowVector::operator==(), vpColVector::operator==(), vpArray2D< Type >::operator==(), vpMatrix::pseudoInverse(), vpMatrix::qr(), vpMatrix::qrPivot(), vpImageTools::remap(), vpHomography::robust(), vpRobotAfma4::setPosition(), vpRobotViper650::setPosition(), vpRobotViper850::setPosition(), vpMbTracker::setProjectionErrorKernelSize(), vpRobotAfma4::setVelocity(), vpRobotAfma6::setVelocity(), vpRobotViper650::setVelocity(), vpRobotViper850::setVelocity(), vpColVector::sort(), vpMatrix::stack(), vpMatrix::stackColumns(), vpMatrix::stackRows(), vpRowVector::stdev(), vpColVector::stdev(), vpMatrix::svdEigen3(), vpMatrix::svdLapack(), vpMatrix::svdOpenCV(), vpTranslationVector::t(), vpPoseVector::t(), vpRowVector::t(), vpColVector::t(), vpTemplateTrackerMIESM::trackNoPyr(), vpMatrix::transpose(), vp::visp2eigen(), vpArray2D< double >::vpArray2D(), vpColVector::vpColVector(), and vpMbTracker::vpMbTracker().

template<class Type>
unsigned int vpArray2D< Type >::dsize
protected

Current array size (rowNum * colNum)

Definition at line 141 of file vpArray2D.h.

Referenced by vpArray2D< Type >::hadamard(), vpArray2D< double >::reshape(), and vpArray2D< double >::resize().