Visual Servoing Platform
version 3.6.1 under development (2024-11-21)
|
#include <visp3/core/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 (const std::vector< Type > &vec, unsigned int r=0, unsigned int c=0) | |
virtual | ~vpArray2D () |
Public Attributes | |
Type * | data |
Related Functions | |
(Note that these are not member functions.) | |
enum | vpGEMMmethod |
template<> | |
bool | operator== (const vpArray2D< double > &A) const |
template<> | |
bool | operator== (const vpArray2D< float > &A) const |
template<class Type > | |
bool | operator!= (const vpArray2D< Type > &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) |
void | insert (const vpArray2D< Type > &A, unsigned int r, unsigned int c) |
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) |
Type * | operator[] (unsigned int i) |
Type * | operator[] (unsigned int i) const |
vpArray2D< Type > | hadamard (const vpArray2D< Type > &m) const |
vpArray2D< Type > | t () const |
Inherited I/O from vpArray2D with Static Public Member Functions | |
static void | insert (const vpArray2D< Type > &A, const vpArray2D< Type > &B, vpArray2D< Type > &C, unsigned int r, unsigned int c) |
unsigned int | rowNum |
unsigned int | colNum |
Type ** | rowPtrs |
unsigned int | dsize |
vpArray2D< Type > | insert (const vpArray2D< Type > &A, const vpArray2D< Type > &B, unsigned int r, unsigned int c) |
static bool | load (const std::string &filename, vpArray2D< Type > &A, bool binary=false, char *header=nullptr) |
static bool | loadYAML (const std::string &filename, vpArray2D< Type > &A, char *header=nullptr) |
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="") |
static vpArray2D< Type > | conv2 (const vpArray2D< Type > &M, const vpArray2D< Type > &kernel, const std::string &mode) |
static void | conv2 (const vpArray2D< Type > &M, const vpArray2D< Type > &kernel, vpArray2D< Type > &res, const std::string &mode) |
template<class T > | |
void | from_json (const nlohmann::json &j, vpArray2D< T > &array) |
template<class T > | |
void | to_json (nlohmann::json &j, const vpArray2D< T > &array) |
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:
Once build, this previous code produces the following output:
If ViSP is build with c++11 enabled, you can do the same using:
The array could also be initialized using operator=(const std::initializer_list< std::initializer_list< Type > > &)
You can also use reshape() function:
Definition at line 144 of file vpArray2D.h.
Basic constructor of a 2D array. Number of columns and rows are set to zero.
Definition at line 154 of file vpArray2D.h.
Copy constructor of a 2D array.
Definition at line 159 of file vpArray2D.h.
References vpArray2D< Type >::colNum, vpArray2D< Type >::data, vpArray2D< Type >::resize(), and vpArray2D< Type >::rowNum.
Constructor that initializes a 2D array with 0.
r | : Array number of rows. |
c | : Array number of columns. |
Definition at line 177 of file vpArray2D.h.
References vpArray2D< Type >::resize().
|
inline |
Constructor that initialize a 2D array with val.
r | : Array number of rows. |
c | : Array number of columns. |
val | : Each element of the array is set to val. |
Definition at line 195 of file vpArray2D.h.
References vpArray2D< Type >::resize().
|
inline |
Constructor that initialize a 2D array from a std::vector.
r | : Array number of rows. |
c | : Array number of columns. |
vec | : Data used to initialize the 2D array. |
Definition at line 218 of file vpArray2D.h.
References vpArray2D< Type >::data, vpException::dimensionError, and vpArray2D< Type >::resize().
Destructor that deallocate memory.
Definition at line 314 of file vpArray2D.h.
References vpArray2D< Type >::colNum, vpArray2D< Type >::data, vpArray2D< Type >::dsize, vpArray2D< Type >::rowNum, and vpArray2D< Type >::rowPtrs.
|
static |
Perform a 2D convolution similar to Matlab conv2 function: .
M | : First matrix. |
kernel | : Second matrix. |
mode | : Convolution mode: "full" (default), "same", "valid". |
Definition at line 1177 of file vpArray2D.h.
Referenced by vpImageFilter::getSobelKernelY().
|
static |
Perform a 2D convolution similar to Matlab conv2 function: .
M | : First array. |
kernel | : Second array. |
res | : Result. |
mode | : Convolution mode: "full" (default), "same", "valid". |
Definition at line 1184 of file vpArray2D.h.
References vpArray2D< Type >::data, vpArray2D< Type >::getCols(), vpArray2D< Type >::getRows(), vpArray2D< Type >::insert(), and vpArray2D< Type >::resize().
|
inline |
Return the number of columns of the 2D array.
Definition at line 337 of file vpArray2D.h.
References vpArray2D< Type >::colNum.
Referenced by vpMatrix::add2Matrices(), vpMatrix::add2WeightedMatrices(), vpQuadProg::checkDimensions(), vpSubMatrix::checkParentStatus(), vpSubRowVector::checkParentStatus(), vpLinProg::colReduction(), vpServo::computeControlLaw(), vpMatrix::computeCovarianceMatrix(), vpMatrix::computeHLM(), vpServo::computeInteractionMatrix(), vpMbTracker::computeJTR(), vpImageFilter::computePartialDerivatives(), vpServo::computeProjectionOperators(), vpMbGenericTracker::computeVVS(), vpMbTracker::computeVVSPoseEstimation(), vpArray2D< Type >::conv2(), vpMatrix::conv2(), vpImageFilter::filter(), vpQuadProg::fromCanonicalCost(), vpImageSimulator::getImage(), vpImageFilter::getScharrKernelX(), vpImageFilter::getSobelKernelX(), vpImageFilter::getSobelKernelY(), vpLuminanceDCT::vpMatrixZigZagIndex::getValues(), vpArray2D< Type >::hadamard(), vpColVector::hadamard(), vpMatrix::hadamard(), vpRowVector::hadamard(), vpUnscentedKalman::init(), vpMatrix::init(), vpRowVector::init(), vpSubMatrix::init(), vpSubRowVector::init(), vpTemplateTrackerSSDInverseCompositional::initCompInverse(), vpCameraParameters::initFromCalibrationMatrix(), vpCircleHoughTransform::initGradientFilters(), vpArray2D< Type >::insert(), vpMatrix::insert(), vpRowVector::insert(), vpLuminanceDCT::inverse(), vpHomography::inverse(), vpMatrix::inverseByCholeskyLapack(), vpMatrix::juxtaposeMatrices(), vpMatrix::kron(), vpLuminancePCA::learn(), vpMeEllipse::leastSquareRobustCircle(), vpMeEllipse::leastSquareRobustEllipse(), vpLuminancePCA::load(), vpLuminanceDCT::map(), vpRowVector::mean(), vpMatrix::mult2Matrices(), vpMatrix::multMatrixVector(), vpForceTwistMatrix::operator*(), vpRotationMatrix::operator*(), vpRowVector::operator*(), vpVelocityTwistMatrix::operator*(), vpColVector::operator*(), vpTranslationVector::operator*(), vpMatrix::operator*(), vpRowVector::operator+(), vpMatrix::operator+=(), vpRowVector::operator+=(), vpRowVector::operator-(), vpMatrix::operator-=(), vpRowVector::operator-=(), vpMatrix::operator=(), vpSubColVector::operator=(), vpSubMatrix::operator=(), vpHomography::operator=(), vpColVector::operator=(), vpRotationMatrix::operator=(), vpRowVector::operator=(), vpSubRowVector::operator=(), vpMatrix::printSize(), vpIoTools::readConfigVar(), vpColVector::reshape(), vpRowVector::reshape(), vpLinProg::rowReduction(), vpArray2D< Type >::save(), vpArray2D< Type >::saveYAML(), vpServo::secondaryTask(), vpServo::secondaryTaskJointLimitAvoidance(), vpLuminanceDCT::vpMatrixZigZagIndex::setValues(), vpQuadProg::solveByProjection(), vpLinProg::solveLP(), vpQuadProg::solveQP(), vpQuadProg::solveQPe(), vpQuadProg::solveQPi(), vpQuadProg::solveSVDorQR(), vpMatrix::stack(), vpRowVector::stack(), vpMatrix::stackRows(), vpMatrix::sub2Matrices(), vpMatrix::svdEigen3(), VISP_NAMESPACE_NAME::visp2eigen(), vpColVector::vpColVector(), vpRowVector::vpRowVector(), and vpImageTools::warpImage().
Type vpArray2D< Type >::getMaxValue |
Return the array max value.
Definition at line 1130 of file vpArray2D.h.
Referenced by vpMatrix::dampedInverse().
Type vpArray2D< Type >::getMinValue |
Return the array min value.
Definition at line 1113 of file vpArray2D.h.
|
inline |
Return the number of rows of the 2D array.
Definition at line 347 of file vpArray2D.h.
References vpArray2D< Type >::rowNum.
Referenced by vpMatrix::add2Matrices(), vpMatrix::add2WeightedMatrices(), vpLinProg::allClose(), vpLinProg::allGreater(), vpLinProg::allLesser(), vpLinProg::allZero(), vpQuadProg::checkDimensions(), vpSubColVector::checkParentStatus(), vpSubMatrix::checkParentStatus(), vpLinProg::colReduction(), vpServo::computeControlLaw(), vpMatrix::computeCovarianceMatrix(), vpServo::computeError(), vpMatrix::computeHLM(), vpServo::computeInteractionMatrix(), vpMbTracker::computeJTR(), vpPtu46::computeMGD(), vpImageFilter::computePartialDerivatives(), vpMbDepthDenseTracker::computeVVS(), vpMbDepthNormalTracker::computeVVS(), vpMbEdgeTracker::computeVVS(), vpMbGenericTracker::computeVVS(), vpMbTracker::computeVVSCheckLevenbergMarquardt(), vpMbEdgeTracker::computeVVSFirstPhasePoseEstimation(), vpMbDepthDenseTracker::computeVVSInteractionMatrixAndResidu(), vpMbTracker::computeVVSPoseEstimation(), vpMbEdgeTracker::computeVVSWeights(), vpMbTracker::computeVVSWeights(), vpArray2D< Type >::conv2(), vpMatrix::conv2(), vpMatrix::createDiagonalMatrix(), vpColVector::crossProd(), vpDot2::defineDots(), vpMatrix::diag(), vpProjectionDisplay::display(), vpColVector::dotProd(), vpGenericFeature::error(), vpImageFilter::filter(), vpQuadProg::fromCanonicalCost(), vpBiclops::get_eJe(), vpPtu46::get_eJe(), vpBiclops::get_fJe(), vpPtu46::get_fJe(), vpBiclops::get_fMe(), vpGenericFeature::get_s(), vpBasicFeature::getDimension(), vpImageSimulator::getImage(), vpAfma6::getInverseKinematics(), vpViper::getInverseKinematicsWrist(), vpImageFilter::getScharrKernelX(), vpImageFilter::getSobelKernelX(), vpImageFilter::getSobelKernelY(), vpLuminanceDCT::vpMatrixZigZagIndex::getValues(), vpArray2D< Type >::hadamard(), vpColVector::hadamard(), vpMatrix::hadamard(), vpRowVector::hadamard(), vpLuminancePCA::init(), vpUnscentedKalman::init(), vpColVector::init(), vpMatrix::init(), vpSubColVector::init(), vpSubMatrix::init(), vpTemplateTrackerSSDInverseCompositional::initCompInverse(), vpCameraParameters::initFromCalibrationMatrix(), vpCircleHoughTransform::initGradientFilters(), vpArray2D< Type >::insert(), vpMatrix::insert(), vpGenericFeature::interaction(), vpLuminanceDCT::inverse(), vpHomography::inverse(), vpMatrix::inverseByCholeskyLapack(), vpMatrix::inverseByQRLapack(), vpColVector::invSort(), vpMatrix::juxtaposeMatrices(), vpMatrix::kernel(), vpScale::KernelDensity(), vpScale::KernelDensityGradient(), vpMatrix::kron(), vpLuminancePCA::learn(), vpMeEllipse::leastSquare(), vpLuminanceDCT::map(), vpColVector::mean(), vpScale::MeanShift(), vpRobust::MEstimator(), vpMatrix::mult2Matrices(), vpMatrix::multMatrixVector(), vpHomogeneousMatrix::operator*(), vpRowVector::operator*(), vpColVector::operator*(), vpForceTwistMatrix::operator*(), vpRotationMatrix::operator*(), vpVelocityTwistMatrix::operator*(), vpMatrix::operator*(), vpColVector::operator+(), vpMatrix::operator+=(), vpColVector::operator+=(), vpColVector::operator-(), vpMatrix::operator-=(), vpColVector::operator-=(), vpMatrix::operator=(), vpRGBa::operator=(), vpRGBf::operator=(), vpSubMatrix::operator=(), vpSubRowVector::operator=(), vpHomography::operator=(), vpColVector::operator=(), vpRotationMatrix::operator=(), vpRowVector::operator=(), vpSubColVector::operator=(), vpPlot::plot(), vpPose::poseVirtualVSrobust(), vpKalmanFilter::prediction(), vpMatrix::printSize(), vpLine::projection(), vpIoTools::readConfigVar(), vpColVector::reshape(), vpRowVector::reshape(), vpLinProg::rowReduction(), vpArray2D< Type >::save(), vpArray2D< Type >::saveYAML(), vpGenericFeature::set_s(), vpQuadProg::setEqualityConstraint(), vpGenericFeature::setError(), vpMbTracker::setEstimatedDoF(), vpGenericFeature::setInteractionMatrix(), vpRobotAfma4::setPosition(), vpLuminanceDCT::vpMatrixZigZagIndex::setValues(), vpRobotBiclops::setVelocity(), vpRobotPololuPtu::setVelocity(), vpRobotPtu46::setVelocity(), vpRobotAfma4::setVelocity(), vpLine::setWorldCoordinates(), vpLinProg::simplex(), 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(), VISP_NAMESPACE_NAME::visp2eigen(), vpColVector::vpColVector(), vpRowVector::vpRowVector(), and vpImageTools::warpImage().
vpArray2D< Type > vpArray2D< Type >::hadamard | ( | const vpArray2D< Type > & | m | ) | const |
Compute the Hadamard product (element wise matrix multiplication).
m | : Second matrix; |
Definition at line 1150 of file vpArray2D.h.
References vpArray2D< Type >::data, vpException::dimensionError, vpArray2D< Type >::getCols(), vpArray2D< Type >::getRows(), and vpArray2D< Type >::resize().
vpArray2D< Type > vpArray2D< Type >::insert | ( | const vpArray2D< Type > & | A, |
const vpArray2D< Type > & | B, | ||
unsigned int | r, | ||
unsigned int | c | ||
) |
Insert array B in array A at the given position.
A | : Main array. |
B | : Array to insert. |
r | : Index of the row where to add the array. |
c | : Index of the column where to add the array. |
Definition at line 1261 of file vpArray2D.h.
References vpArray2D< Type >::insert().
|
inline |
Insert array A at the given position in the current array.
A | : The array to insert. |
r | : The index of the row to begin to insert data. |
c | : The index of the column to begin to insert data. |
Definition at line 497 of file vpArray2D.h.
References vpArray2D< Type >::colNum, vpArray2D< Type >::data, vpException::dimensionError, vpArray2D< Type >::getCols(), vpArray2D< Type >::getRows(), vpArray2D< Type >::rowNum, and vpArray2D< Type >::size().
Referenced by vpArray2D< Type >::conv2(), vpMatrix::insert(), vpPioneerPan::set_mMp(), and vpPioneerPan::set_pMe().
|
inlinestatic |
Load a matrix from a file.
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. |
Definition at line 669 of file vpArray2D.h.
References vpException::badValue, and vpArray2D< Type >::resize().
Referenced by vpMatrix::loadMatrix().
|
inlinestatic |
Load an array from a YAML-formatted file.
filename | : absolute file name. |
A | : array to be loaded from the file. |
header | : header of the file is loaded in this parameter. |
Definition at line 783 of file vpArray2D.h.
References vpArray2D< Type >::resize().
Referenced by vpMatrix::loadMatrixYAML().
bool operator!= | ( | const vpArray2D< Type > & | A | ) | const |
Not equal to comparison operator of a 2D array.
Definition at line 1351 of file vpArray2D.h.
|
inline |
Copy operator of a 2D array.
Definition at line 535 of file vpArray2D.h.
References vpArray2D< Type >::colNum, vpArray2D< Type >::data, vpArray2D< Type >::resize(), and vpArray2D< Type >::rowNum.
Set all the elements of the array to x.
Definition at line 526 of file vpArray2D.h.
References vpArray2D< Type >::data, and vpArray2D< Type >::dsize.
Equal to comparison operator of a 2D array.
Definition at line 1294 of file vpArray2D.h.
References vpArray2D< Type >::colNum, vpArray2D< Type >::data, vpArray2D< Type >::rowNum, and vpArray2D< Type >::size().
|
inline |
Set element using A[i][j] = x.
Definition at line 605 of file vpArray2D.h.
References vpArray2D< Type >::rowPtrs.
|
inline |
Get element using x = A[i][j].
Definition at line 607 of file vpArray2D.h.
References vpArray2D< Type >::rowPtrs.
|
inline |
Definition at line 456 of file vpArray2D.h.
References vpArray2D< Type >::colNum, vpArray2D< Type >::data, vpException::dimensionError, vpArray2D< Type >::dsize, vpArray2D< Type >::resize(), vpArray2D< Type >::rowNum, and vpArray2D< Type >::rowPtrs.
|
inline |
Set the size of the array and initialize all the values to zero.
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 362 of file vpArray2D.h.
References vpArray2D< Type >::colNum, vpArray2D< Type >::dsize, vpException::memoryAllocationError, vpArray2D< Type >::rowNum, and vpArray2D< Type >::rowPtrs.
Referenced by vpMatrix::AAt(), vpMatrix::add2Matrices(), vpMatrix::add2WeightedMatrices(), vpMatrix::AtA(), vpLinProg::colReduction(), vpServo::computeProjectionOperators(), vpMbDepthDenseTracker::computeVVSInit(), vpMbDepthNormalTracker::computeVVSInit(), vpMbEdgeTracker::computeVVSInit(), vpMbGenericTracker::computeVVSInit(), vpMatrix::cond(), vpArray2D< Type >::conv2(), vpMatrix::conv2(), vpMatrix::createDiagonalMatrix(), vpProjectionDisplay::display(), vpHomography::DLT(), VISP_NAMESPACE_NAME::eigen2visp(), vpMatrix::eigenValues(), vpMatrix::expm(), vpMatrix::extract(), vpRobotFlirPtu::get_eJe(), vpAfma4::get_eJe(), vpAfma6::get_eJe(), vpBiclops::get_eJe(), vpPtu46::get_eJe(), vpRobotPololuPtu::get_eJe(), vpRobotFranka::get_eJe(), vpRobotFlirPtu::get_fJe(), vpAfma4::get_fJe(), vpAfma6::get_fJe(), vpBiclops::get_fJe(), vpPtu46::get_fJe(), vpRobotPololuPtu::get_fJe(), vpRobotFranka::get_fJe(), vpAfma4::get_fJe_inverse(), vpViper::get_fJw(), vpRobotFranka::getMass(), vpArray2D< Type >::hadamard(), vpMatrix::hadamard(), vpLuminanceMapping::imageAsMatrix(), vpProjectionDisplay::init(), vpKalmanFilter::init(), vpTemplateTrackerMIESM::initCompInverse(), vpCircleHoughTransform::initGaussianFilters(), vpCircleHoughTransform::initGradientFilters(), vpMbtDistanceCircle::initInteractionMatrixError(), vpMbtDistanceCylinder::initInteractionMatrixError(), vpMbtDistanceLine::initInteractionMatrixError(), vpTemplateTracker::initTracking(), vpImageTools::initUndistortMap(), vpArray2D< Type >::insert(), vpGenericFeature::interaction(), vpMatrix::inverseByLU(), vpMatrix::inverseByQRLapack(), vpMatrix::inverseTriangular(), vpMatrix::juxtaposeMatrices(), vpMatrix::kernel(), vpMatrix::kron(), vpLuminancePCA::learn(), vpArray2D< Type >::load(), vpArray2D< Type >::loadYAML(), vpMatrix::mult2Matrices(), vpMatrix::negateMatrix(), vpMatrix::nullSpace(), vpMatrix::operator*(), vpMatrix::operator/(), vpArray2D< Type >::operator=(), vpRotationVector::operator=(), vpPose::poseVirtualVSrobust(), vpMatrix::qr(), vpIoTools::readConfigVar(), vpArray2D< Type >::reshape(), vpColVector::reshape(), vpRowVector::reshape(), vpColVector::resize(), vpRowVector::resize(), vpLinProg::rowReduction(), vpServo::secondaryTask(), vpMbTracker::setProjectionErrorKernelSize(), vpColVector::skew(), vpTranslationVector::skew(), vpLinProg::solveLP(), vpQuadProg::solveQPi(), vpMatrix::stack(), vpMatrix::sub2Matrices(), vpMatrix::svdEigen3(), vpMatrix::svdLapack(), vpMatrix::svdOpenCV(), vpMatrix::transpose(), vpArray2D< Type >::vpArray2D(), vpTemplateTrackerMI::vpTemplateTrackerMI(), vpTemplateTrackerSSD::vpTemplateTrackerSSD(), vpTemplateTrackerSSDESM::vpTemplateTrackerSSDESM(), vpTemplateTrackerSSDInverseCompositional::vpTemplateTrackerSSDInverseCompositional(), vpTemplateTrackerWarpHomographySL3::vpTemplateTrackerWarpHomographySL3(), and vpTemplateTrackerZNCC::vpTemplateTrackerZNCC().
|
inlinestatic |
Save a matrix to a file.
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. |
Warning : If you save the matrix as in a text file the precision is less than if you save it in a binary file.
Definition at line 874 of file vpArray2D.h.
References vpArray2D< Type >::getCols(), and vpArray2D< Type >::getRows().
Referenced by vpMatrix::saveMatrix().
|
inlinestatic |
Save an array in a YAML-formatted file.
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. |
Here is an example of outputs.
Content of matrix.yml:
Content of matrixIndent.yml:
Definition at line 972 of file vpArray2D.h.
References vpArray2D< Type >::getCols(), and vpArray2D< Type >::getRows().
Referenced by vpMatrix::saveMatrixYAML().
|
inline |
Return the number of elements of the 2D array.
Definition at line 349 of file vpArray2D.h.
References vpArray2D< Type >::colNum, and vpArray2D< Type >::rowNum.
Referenced by vpVirtuose::addForce(), vpForceTorqueAtiSensor::bias(), vpQuaternionVector::buildFrom(), vpRxyzVector::buildFrom(), vpRzyxVector::buildFrom(), vpRzyzVector::buildFrom(), vpThetaUVector::buildFrom(), vpTranslationVector::buildFrom(), vpMbtFaceDepthNormal::computeNormalVisibility(), vpMath::deg(), vpExponentialMap::direct(), vpColVector::dotProd(), vpMbtFaceDepthNormal::estimatePlaneEquationSVD(), vpRobotPololuPtu::get_eJe(), vpRobotFranka::get_fJe(), vpRobotPololuPtu::get_fJe(), vpRobotFranka::get_fMe(), vpRobotUniversalRobots::get_fMe(), vpForceTorqueAtiSensor::getForceTorque(), vpMeEllipse::getParameters(), vpPoint::getWorldCoordinates(), vpMatrix::inducedL2Norm(), vpParticleFilter< MeasurementsType >::init(), vpImageTools::inRange(), vpArray2D< Type >::insert(), vpMatrix::insert(), vpColVector::insert(), vpRowVector::insert(), vpMath::lineFitting(), vpMath::lookAt(), vpHomogeneousMatrix::mean(), vpRotationMatrix::mean(), vpColVector::mean(), vpRowVector::mean(), vpMarkersMeasurements::measureWithNoise(), vpColVector::median(), vpRowVector::median(), vpHomography::operator*(), vpColVector::operator*(), vpTranslationVector::operator+(), vpQuaternionVector::operator=(), vpRxyzVector::operator=(), vpRzyxVector::operator=(), vpRzyzVector::operator=(), vpThetaUVector::operator=(), vpTranslationVector::operator=(), vpRotationVector::operator=(), vpArray2D< Type >::operator==(), vpPlot::plot(), vpMath::rad(), vpRobot::saturateVelocities(), vpServo::secondaryTaskJointLimitAvoidance(), vpImageFilter::sepFilter(), vpVirtuose::setArticularForce(), vpVirtuose::setArticularPosition(), vpVirtuose::setArticularVelocity(), vpServo::setCameraDoF(), vpRobotFlirPtu::setCartVelocity(), vpRobotKinova::setCartVelocity(), vpRobotTemplate::setCartVelocity(), vpVirtuose::setForce(), vpRobotFranka::setForceTorque(), vpRobotKinova::setJointVelocity(), vpRobotFlirPtu::setPanPosLimits(), vpQbSoftHand::setPosition(), vpReflexTakktile2::setPosition(), vpRobotUniversalRobots::setPosition(), vpRobotFlirPtu::setPosition(), vpRobotKinova::setPosition(), vpRobotPololuPtu::setPosition(), vpReflexTakktile2::setPositioningVelocity(), vpRobotFlirPtu::setTiltPosLimits(), vpLuminanceDCT::vpMatrixZigZagIndex::setValues(), vpRobotBebop2::setVelocity(), vpRobotPololuPtu::setVelocity(), vpRobotFlirPtu::setVelocity(), vpRobotFranka::setVelocity(), vpRobotKinova::setVelocity(), vpRobotPioneer::setVelocity(), vpRobotTemplate::setVelocity(), vpSimulatorPioneer::setVelocity(), vpSimulatorPioneerPan::setVelocity(), vpVirtuose::setVelocity(), vpReflexTakktile2::setVelocityUntilAnyContact(), vpReflexTakktile2::setVelocityUntilEachContact(), vpPoint::setWorldCoordinates(), vpUnscentedKalman::simpleMean(), vpMatrix::stack(), vpColVector::stdev(), vpRowVector::stdev(), vpMatrix::svdEigen3(), vpForceTorqueAtiSensor::unbias(), VISP_NAMESPACE_NAME::visp2eigen(), vpColVector::vpColVector(), vpPanda3DPointLight::vpPanda3DPointLight(), vpTranslationVector::vpTranslationVector(), vpTemplateTrackerWarp::warpTriangle(), and vpParticleFilter< MeasurementsType >::weightedMean().
Compute the transpose of the array.
Definition at line 1166 of file vpArray2D.h.
Referenced by vpImageFilter::getScharrKernelX(), and vpImageFilter::getSobelKernelX().
|
friend |
|
related |
Insert array B in array A at the given position.
A | : Main array. |
B | : Array to insert. |
C | : Result array. |
r | : Index of the row where to insert array B. |
c | : Index of the column where to insert array B. |
Definition at line 1270 of file vpArray2D.h.
References vpException::dimensionError, vpArray2D< Type >::getCols(), vpArray2D< Type >::getRows(), and vpArray2D< Type >::resize().
Referenced by vpArray2D< Type >::insert().
|
related |
Definition at line 1351 of file vpArray2D.h.
|
friend |
Writes the given array to the output stream and returns a reference to the output stream.
Definition at line 614 of file vpArray2D.h.
|
related |
Definition at line 1313 of file vpArray2D.h.
References vpArray2D< Type >::colNum, vpArray2D< Type >::data, vpArray2D< Type >::rowNum, and vpArray2D< Type >::size().
|
related |
Definition at line 1332 of file vpArray2D.h.
References vpArray2D< Type >::colNum, vpArray2D< Type >::data, vpArray2D< Type >::rowNum, and vpArray2D< Type >::size().
|
friend |
|
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 :
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:
vpException::incorrectMatrixSizeError | if the sizes of the matrices do not allow the operations. |
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. |
Definition at line 414 of file vpGEMM.h.
References vpException::functionNotImplementedError.
|
related |
Enumeration of the operations applied on matrices in vpGEMM() function.
Operations are :
|
protected |
Number of columns in the array.
Definition at line 1103 of file vpArray2D.h.
Referenced by vpMatrix::AAt(), vpMatrix::add2Matrices(), vpMatrix::add2WeightedMatrices(), vpMatrix::AtA(), vpArray2D< Type >::getCols(), vpArray2D< Type >::insert(), vpMatrix::insert(), vpMatrix::inverseByQRLapack(), vpMatrix::inverseTriangular(), vpRowVector::median(), vpMatrix::mult2Matrices(), vpMatrix::multMatrixVector(), vpMatrix::negateMatrix(), vpMatrix::operator*(), vpArray2D< Type >::operator=(), vpRowVector::operator=(), vpArray2D< Type >::operator==(), vpColVector::operator==(), vpRowVector::operator==(), vpMatrix::qr(), vpArray2D< Type >::reshape(), vpArray2D< Type >::resize(), vpArray2D< Type >::size(), vpMatrix::stackColumns(), vpMatrix::sub2Matrices(), vpArray2D< Type >::vpArray2D(), vpMatrix::vpMatrix(), and vpArray2D< Type >::~vpArray2D().
Type* vpArray2D< Type >::data |
Address of the first element of the data array.
Definition at line 148 of file vpArray2D.h.
Referenced by vpMatrix::AAt(), vpMatrix::AtA(), vpMatrix::choleskyByLapack(), vpCircleHoughTransform::computeGradients(), vpMbtFaceDepthDense::computeInteractionMatrixAndResidu(), vpMbTracker::computeJTR(), vpImageFilter::computePartialDerivatives(), vpArray2D< Type >::conv2(), vpMatrix::conv2(), vpMatrix::detByLULapack(), vpColVector::dotProd(), VISP_NAMESPACE_NAME::eigen2visp(), vpMatrix::eigenValues(), vpMatrix::expm(), vpRobotViper650::getForceTorque(), vpRobotViper850::getForceTorque(), vpRobotViper650::getPosition(), vpRobotViper850::getPosition(), vpMatrix::getRow(), vpImageFilter::getScharrKernelX(), vpImageFilter::getSobelKernelX(), vpImageFilter::getSobelKernelY(), vpRobotViper650::getVelocity(), vpRobotViper850::getVelocity(), vpArray2D< Type >::hadamard(), vpColVector::hadamard(), vpMatrix::hadamard(), vpRowVector::hadamard(), vpRobotViper650::init(), vpRobotViper850::init(), vpSubColVector::init(), vpSubMatrix::init(), vpSubRowVector::init(), vpCircleHoughTransform::initGaussianFilters(), vpCircleHoughTransform::initGradientFilters(), vpTemplateTrackerMIESM::initHessienDesired(), vpArray2D< Type >::insert(), vpMatrix::insert(), vpColVector::insert(), vpMatrix::inverseByCholeskyLapack(), vpMatrix::inverseByCholeskyOpenCV(), vpMatrix::inverseByLUEigen3(), vpMatrix::inverseByLULapack(), vpMatrix::inverseByLUOpenCV(), vpMatrix::inverseByQRLapack(), vpMatrix::inverseTriangular(), vpColVector::invSort(), vpColVector::mean(), vpRowVector::mean(), vpColVector::median(), vpRowVector::median(), vpMatrix::mult2Matrices(), vpMatrix::multMatrixVector(), vpHomography::operator*(), vpMatrix::operator*(), vpColVector::operator*(), vpRowVector::operator*(), vpTranslationVector::operator*(), vpColVector::operator-(), vpRowVector::operator-(), vpTranslationVector::operator-(), vpHomography::operator/(), vpColVector::operator/(), vpRowVector::operator/(), vpTranslationVector::operator/(), vpMatrix::operator=(), vpTranslationVector::operator=(), vpColVector::operator=(), vpRotationVector::operator=(), vpRowVector::operator=(), vpSubColVector::operator=(), vpArray2D< Type >::operator=(), vpArray2D< Type >::operator==(), vpColVector::operator==(), vpRowVector::operator==(), vpMatrix::qr(), vpImageTools::remap(), vpArray2D< Type >::reshape(), 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(), vpColVector::stdev(), vpRowVector::stdev(), vpMatrix::svdEigen3(), vpMatrix::svdLapack(), vpMatrix::svdOpenCV(), vpColVector::t(), vpPoseVector::t(), vpRowVector::t(), vpTranslationVector::t(), vpTemplateTrackerMIESM::trackNoPyr(), vpMatrix::transpose(), VISP_NAMESPACE_NAME::visp2eigen(), vpArray2D< Type >::vpArray2D(), vpMbTracker::vpMbTracker(), and vpArray2D< Type >::~vpArray2D().
|
protected |
Current array size (rowNum * colNum)
Definition at line 1107 of file vpArray2D.h.
Referenced by vpArray2D< Type >::operator=(), vpArray2D< Type >::reshape(), vpArray2D< Type >::resize(), and vpArray2D< Type >::~vpArray2D().
|
protected |
Number of rows in the array.
Definition at line 1101 of file vpArray2D.h.
Referenced by vpMatrix::AAt(), vpMatrix::add2Matrices(), vpMatrix::add2WeightedMatrices(), vpMatrix::AtA(), vpArray2D< Type >::getRows(), vpArray2D< Type >::insert(), vpColVector::insert(), vpMatrix::inverseByQRLapack(), vpMatrix::inverseTriangular(), vpColVector::median(), vpMatrix::mult2Matrices(), vpMatrix::multMatrixVector(), vpMatrix::negateMatrix(), vpArray2D< Type >::operator=(), vpColVector::operator=(), vpTranslationVector::operator=(), vpArray2D< Type >::operator==(), vpColVector::operator==(), vpRowVector::operator==(), vpMatrix::qr(), vpArray2D< Type >::reshape(), vpArray2D< Type >::resize(), vpArray2D< Type >::size(), vpMatrix::stackColumns(), vpColVector::stdev(), vpMatrix::sub2Matrices(), vpArray2D< Type >::vpArray2D(), vpMatrix::vpMatrix(), and vpArray2D< Type >::~vpArray2D().
|
protected |
Address of the first element of each rows.
Definition at line 1105 of file vpArray2D.h.
Referenced by vpMatrix::add2Matrices(), vpMatrix::add2WeightedMatrices(), vpMatrix::mult2Matrices(), vpMatrix::multMatrixVector(), vpMatrix::negateMatrix(), vpForceTwistMatrix::operator*(), vpRotationMatrix::operator*(), vpVelocityTwistMatrix::operator*(), vpMatrix::operator+=(), vpMatrix::operator-=(), vpForceTwistMatrix::operator=(), vpHomogeneousMatrix::operator=(), vpRotationMatrix::operator=(), vpSubMatrix::operator=(), vpVelocityTwistMatrix::operator=(), vpArray2D< Type >::operator[](), vpArray2D< Type >::reshape(), vpArray2D< Type >::resize(), vpMatrix::sub2Matrices(), and vpArray2D< Type >::~vpArray2D().