39 #include <visp3/core/vpImageConvert.h>
40 #include <visp3/mbt/vpMbKltTracker.h>
41 #include <visp3/core/vpVelocityTwistMatrix.h>
42 #include <visp3/core/vpTrackingException.h>
44 #if defined(VISP_HAVE_MODULE_KLT) && (defined(VISP_HAVE_OPENCV) && (VISP_HAVE_OPENCV_VERSION >= 0x020100))
48 #if (VISP_HAVE_OPENCV_VERSION >= 0x020408)
53 c0Mo(), compute_interaction(true),
54 firstInitialisation(true), maskBorder(5), lambda(0.8), maxIter(200), threshold_outlier(0.5),
55 percentGood(0.6), ctTc0(), tracker(), kltPolygons(), kltCylinders(), circles_disp()
81 #if (VISP_HAVE_OPENCV_VERSION < 0x020408)
90 for(std::list<vpMbtDistanceKltPoints*>::const_iterator it=
kltPolygons.begin(); it!=
kltPolygons.end(); ++it){
101 kltPolyCylinder = *it;
102 if (kltPolyCylinder!=NULL){
103 delete kltPolyCylinder ;
105 kltPolyCylinder = NULL ;
129 bool reInitialisation =
false;
133 #ifdef VISP_HAVE_OGRE
169 #if (VISP_HAVE_OPENCV_VERSION >= 0x020408)
170 cv::Mat mask((
int)I.
getRows(), (int)I.
getCols(), CV_8UC1, cv::Scalar(0));
172 IplImage* mask = cvCreateImage(cvSize((
int)I.
getWidth(), (int)I.
getHeight()), IPL_DEPTH_8U, 1);
182 unsigned char val = 255;
183 for(std::list<vpMbtDistanceKltPoints*>::const_iterator it=
kltPolygons.begin(); it!=
kltPolygons.end(); ++it){
192 kltPolyCylinder = *it;
199 if(
faces[indCylBBox]->isVisible() &&
faces[indCylBBox]->getNbPoint() > 2){
200 faces[indCylBBox]->computePolygonClipped(
cam);
213 for(std::list<vpMbtDistanceKltPoints*>::const_iterator it=
kltPolygons.begin(); it!=
kltPolygons.end(); ++it){
221 kltPolyCylinder = *it;
227 #if (VISP_HAVE_OPENCV_VERSION < 0x020408)
228 cvReleaseImage(&mask);
241 #if (VISP_HAVE_OPENCV_VERSION < 0x020408)
243 cvReleaseImage(&
cur);
250 for(std::list<vpMbtDistanceKltPoints*>::const_iterator it=
kltPolygons.begin(); it!=
kltPolygons.end(); ++it){
261 kltPolyCylinder = *it;
262 if (kltPolyCylinder!=NULL){
263 delete kltPolyCylinder ;
265 kltPolyCylinder = NULL ;
314 #ifdef VISP_HAVE_OGRE
326 std::vector<vpImagePoint>
329 std::vector<vpImagePoint> kltPoints;
347 std::map<int, vpImagePoint>
350 std::map<int, vpImagePoint> kltPoints;
390 for(std::list<vpMbtDistanceKltPoints*>::const_iterator it=
kltPolygons.begin(); it!=
kltPolygons.end(); ++it){
397 kltPolyCylinder = *it;
418 std::cout <<
"WARNING: Cannot set pose when model contains cylinder(s). This feature is not implemented yet." << std::endl;
419 std::cout <<
"Tracker will be reinitialized with the given pose." << std::endl;
427 #if (VISP_HAVE_OPENCV_VERSION >= 0x020408)
428 std::vector<cv::Point2f> init_pts;
429 std::vector<long> init_ids;
430 std::vector<cv::Point2f> guess_pts;
432 unsigned int nbp = 0;
433 for(std::list<vpMbtDistanceKltPoints*>::const_iterator it=
kltPolygons.begin(); it!=
kltPolygons.end(); ++it) {
439 CvPoint2D32f* init_pts = NULL;
442 unsigned int iter_pts = 0;
444 CvPoint2D32f* guess_pts = NULL;
457 unsigned int nbCur = 0;
459 for(std::list<vpMbtDistanceKltPoints*>::const_iterator it=
kltPolygons.begin(); it!=
kltPolygons.end(); ++it) {
472 double invDc = 1.0 / plan.
getD();
476 vpGEMM(cdtc, Nc, -invDc, cdRc, 1.0, cdHc, VP_GEMM_B_T);
483 std::map<int, vpImagePoint>::const_iterator iter = kltpoly->
getCurrentPoints().begin();
487 cdp[0] = iter->second.get_j(); cdp[1] = iter->second.get_i(); cdp[2] = 1.0;
489 #if (VISP_HAVE_OPENCV_VERSION >= 0x020408)
490 cv::Point2f p((
float)cdp[0], (
float)cdp[1]);
491 init_pts.push_back(p);
494 init_pts[iter_pts].x = (float)cdp[0];
495 init_pts[iter_pts].y = (float)cdp[1];
499 double p_mu_t_2 = cdp[0] * cdGc[2][0] + cdp[1] * cdGc[2][1] + cdGc[2][2];
501 if( fabs(p_mu_t_2) < std::numeric_limits<double>::epsilon()){
507 cdp[0] = (cdp[0] * cdGc[0][0] + cdp[1] * cdGc[0][1] + cdGc[0][2]) / p_mu_t_2;
508 cdp[1] = (cdp[0] * cdGc[1][0] + cdp[1] * cdGc[1][1] + cdGc[1][2]) / p_mu_t_2;
511 #if (VISP_HAVE_OPENCV_VERSION >= 0x020408)
512 cv::Point2f p_guess((
float)cdp[0], (
float)cdp[1]);
513 guess_pts.push_back(p_guess);
515 guess_pts[iter_pts].x = (float)cdp[0];
516 guess_pts[iter_pts++].y = (float)cdp[1];
524 #if (VISP_HAVE_OPENCV_VERSION >= 0x020408)
529 if(init_pts) cvFree(&init_pts);
532 if(guess_pts) cvFree(&guess_pts);
535 if(init_ids)cvFree(&init_ids);
539 bool reInitialisation =
false;
543 #ifdef VISP_HAVE_OGRE
557 for(std::list<vpMbtDistanceKltPoints*>::const_iterator it=
kltPolygons.begin(); it!=
kltPolygons.end(); ++it){
619 for(std::list<vpMbtDistanceKltPoints*>::const_iterator it=
kltPolygons.begin(); it!=
kltPolygons.end(); ++it){
633 kltPolyCylinder = *it;
654 bool reInitialisation =
false;
656 unsigned int initialNumber = 0;
657 unsigned int currentNumber = 0;
658 unsigned int shift = 0;
661 for(std::list<vpMbtDistanceKltPoints*>::const_iterator it=
kltPolygons.begin(); it!=
kltPolygons.end(); ++it){
681 kltPolyCylinder = *it;
697 double value =
percentGood * (double)initialNumber;
698 if((
double)currentNumber < value){
700 reInitialisation =
true;
706 #ifdef VISP_HAVE_OGRE
748 double normRes_1 = -1;
749 unsigned int iter = 0;
752 L.
resize(2*nbInfos, 6, 0);
754 while( ((
int)((normRes - normRes_1)*1e8) != 0 ) && (iter<
maxIter) ){
756 unsigned int shift = 0;
759 for(std::list<vpMbtDistanceKltPoints*>::const_iterator it=
kltPolygons.begin(); it!=
kltPolygons.end(); ++it){
778 kltPolyCylinder = *it;
794 bool reStartFromLastIncrement =
false;
805 reStartFromLastIncrement =
true;
809 if(!reStartFromLastIncrement){
826 LVJ_true = (L*cVo*
oJo);
832 for (
unsigned int i = 0; i < static_cast<unsigned int>(R.
getRows()); i += 1){
839 for(
unsigned int i=0; i<static_cast<unsigned int>(R.
getRows()); i++){
840 for(
unsigned int j=0; j<6; j++){
882 vpMatrix LTLmuI = LVJTLVJ + (LMA*mu);
935 unsigned int nbInfos = 0;
936 unsigned int nbFaceUsed = 0;
945 if(nbInfos < 4 || nbFaceUsed == 0){
1023 #ifdef VISP_HAVE_XML2
1038 std::cout <<
" *********** Parsing XML for MBT KLT Tracker ************ " << std::endl;
1039 xmlp.
parse(configFile);
1086 vpTRACE(
"You need the libXML2 to read the config file %s", configFile);
1102 const vpColor& col,
const unsigned int thickness,
const bool displayFullModel)
1123 for(std::list<vpMbtDistanceKltPoints*>::const_iterator it=
kltPolygons.begin(); it!=
kltPolygons.end(); ++it){
1126 kltpoly->
display(I,cMo_,camera,col,thickness,displayFullModel);
1135 kltPolyCylinder = *it;
1137 kltPolyCylinder->
display(I,cMo_,camera,col,thickness,displayFullModel);
1144 (*it)->display(I, cMo_, camera, col, thickness, displayFullModel);
1147 #ifdef VISP_HAVE_OGRE
1165 const vpColor& col ,
const unsigned int thickness,
const bool displayFullModel)
1186 for(std::list<vpMbtDistanceKltPoints*>::const_iterator it=
kltPolygons.begin(); it!=
kltPolygons.end(); ++it){
1189 kltpoly->
display(I,cMo_,camera,col,thickness,displayFullModel);
1198 kltPolyCylinder = *it;
1200 kltPolyCylinder->
display(I,cMo_,camera,col,thickness,displayFullModel);
1207 (*it)->display(I, cMo_, camera, col, thickness);
1210 #ifdef VISP_HAVE_OGRE
1227 unsigned int nbTotalPoints = 0;
1230 for(std::list<vpMbtDistanceKltPoints*>::const_iterator it=
kltPolygons.begin(); it!=
kltPolygons.end(); ++it){
1239 kltPolyCylinder = *it;
1244 if(nbTotalPoints < 10){
1245 std::cerr <<
"test tracking failed (too few points to realize a good tracking)." << std::endl;
1247 "test tracking failed (too few points to realize a good tracking).");
1263 const std::string &)
1293 const int ,
const std::string &name)
1310 bool already_here = false ;
1362 #if (VISP_HAVE_OPENCV_VERSION < 0x020408)
1364 cvReleaseImage(&
cur);
1387 for(std::list<vpMbtDistanceKltPoints*>::const_iterator it=
kltPolygons.begin(); it!=
kltPolygons.end(); ++it){
1395 #elif !defined(VISP_BUILD_SHARED_LIBS)
1397 void dummy_vpMbKltTracker() {};
1398 #endif //VISP_HAVE_OPENCV
void setKltOpencv(const vpKltOpencv &t)
bool compute_interaction
If true, compute the interaction matrix at each iteration of the minimization. Otherwise, compute it only on the first iteration.
void addCircle(const vpPoint &P1, const vpPoint &P2, const vpPoint &P3, const double r, const std::string &name="")
virtual void track(const vpImage< unsigned char > &I)
unsigned int getCols() const
vpMatrix get_K_inverse() const
void setWindowName(const Ogre::String &n)
std::list< vpMbtDistanceKltPoints * > kltPolygons
int getPyramidLevels() const
Get the list of features id.
unsigned int getMaskBorder() const
void setQuality(const double &q)
Implementation of a matrix and operations on matrices.
vpMatrix covarianceMatrix
Covariance matrix.
void displayPrimitive(const vpImage< unsigned char > &_I)
void setTracked(const bool &track)
virtual ~vpMbKltTracker()
double getHarrisParam() const
static vpMatrix computeCovarianceMatrixVVS(const vpHomogeneousMatrix &cMo, const vpColVector &deltaS, const vpMatrix &Ls, const vpMatrix &W)
void reInitModel(const vpImage< unsigned char > &I, const std::string &cad_name, const vpHomogeneousMatrix &cMo_, const bool verbose=false)
unsigned int computeNbDetectedCurrent(const vpKltOpencv &_tracker)
void setCameraParameters(const vpCameraParameters &camera)
void init(const vpKltOpencv &_tracker)
void MEstimator(const vpRobustEstimatorType method, const vpColVector &residues, vpColVector &weights)
Compute the weights according a residue vector and a PsiFunction.
void removeOutliers(const vpColVector &weight, const double &threshold_outlier)
void setUseKltTracking(const std::string &name, const bool &useKltTracking)
void setHarrisFreeParameter(double harris_k)
int getMaxFeatures() const
Get the list of lost feature.
void parse(const char *filename)
unsigned int getWidth() const
static void convert(const vpImage< unsigned char > &src, vpImage< vpRGBa > &dest)
void resize(const unsigned int nrows, const unsigned int ncols, const bool flagNullify=true)
void getCameraParameters(vpCameraParameters &_cam) const
vpMbHiddenFaces< vpMbtPolygon > faces
Set of faces describing the object.
unsigned int maxIter
The maximum iteration of the virtual visual servoing stage.
void removeOutliers(const vpColVector &weight, const double &threshold_outlier)
Implementation of an homogeneous matrix and operations on such kind of matrices.
std::vector< int > listIndicesCylinderBBox
Pointer to the polygon that define a face.
double getHarrisFreeParameter() const
Get the free parameter of the Harris detector.
virtual void initFaceFromCorners(vpMbtPolygon &polygon)
Class to define colors available for display functionnalities.
void setMaxFeatures(const int maxCount)
double percentGood
Percentage of good points, according to the initial number, that must have the tracker.
void setBackgroundSizeOgre(const unsigned int &h, const unsigned int &w)
virtual void initCylinder(const vpPoint &, const vpPoint &, const double, const int, const std::string &name="")
vpMbHiddenFaces< vpMbtPolygon > * hiddenface
Pointer to the list of faces.
vpHomogeneousMatrix cMo
The current pose.
bool postTracking(const vpImage< unsigned char > &I, vpColVector &w)
unsigned int getBlockSize() const
bool hasEnoughPoints() const
double getNearClippingDistance() const
void setOgreShowConfigDialog(const bool showConfigDialog)
bool modelInitialised
Flag used to ensure that the CAD model is loaded before the initialisation.
void setMinDistance(double minDistance)
void buildFrom(const vpPoint &_p1, const vpPoint &_p2, const vpPoint &_p3, const double r)
error that can be emited by ViSP classes.
vpMbScanLine & getMbScanLineRenderer()
vpPoint * p
corners in the object frame
unsigned int getMaxFeatures() const
void init(const vpKltOpencv &_tracker, const vpHomogeneousMatrix &cMo)
bool useOgre
Use Ogre3d for visibility tests.
unsigned int getCols() const
Return the number of columns of the 2D array.
virtual void initFromPose(const vpImage< unsigned char > &I, const std::string &initFile)
Definition of the vpSubMatrix vpSubMatrix class provides a mask on a vpMatrix all properties of vpMat...
unsigned int setVisibleOgre(const vpImage< unsigned char > &I, const vpCameraParameters &cam, const vpHomogeneousMatrix &cMo, const double &angleAppears, const double &angleDisappears, bool &changed)
bool computeCovariance
Flag used to specify if the covariance matrix has to be computed or not.
bool firstInitialisation
Flag to specify whether the init method is called the first or not (specific calls to realize in this...
virtual void reinit(const vpImage< unsigned char > &I)
Implementation of a polygon of the model containing points of interest. It is used by the model-based...
virtual void testTracking()
bool hasNearClippingDistance() const
Class that defines what is a point.
virtual void loadConfigFile(const std::string &configFile)
unsigned int getInitialNumberPoint() const
vpCameraParameters cam
The camera parameters.
void computeClippedPolygons(const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam)
unsigned int setVisible(const vpImage< unsigned char > &I, const vpCameraParameters &cam, const vpHomogeneousMatrix &cMo, const double &angle, bool &changed)
Implementation of a rotation matrix and operations on such kind of matrices.
void setQuality(double qualityLevel)
vpHomogeneousMatrix ctTc0
The estimated displacement of the pose between the current instant and the initial position...
std::map< int, int > & getCurrentPointsInd()
double getFarClippingDistance() const
void initOgre(const vpCameraParameters &cam=vpCameraParameters())
bool hasFarClippingDistance() const
unsigned int computeNbDetectedCurrent(const vpKltOpencv &_tracker)
Implementation of an homography and operations on homographies.
vpAROgre * getOgreContext()
void changeFrame(const vpHomogeneousMatrix &cMo)
unsigned int getRows() const
std::vector< vpImagePoint > getKltImagePoints() const
void setPyramidLevels(const unsigned int &pL)
virtual void setMinPolygonAreaThresh(const double minPolygonAreaThresh, const std::string &name="")
vpColVector & normalize()
Parse an Xml file to extract configuration parameters of a Mbt Klt object.Data parser for the KLT mod...
Manage a circle used in the model-based tracker.
vpMatrix oJo
The Degrees of Freedom to estimate.
unsigned int getWindowSize() const
Error that can be emited by the vpTracker class and its derivates.
double getAngleDisappear() const
Implementation of a polygon of the model used by the model-based tracker.
virtual void setCameraParameters(const vpCameraParameters &_cam)
void computePolygonClipped(const vpCameraParameters &cam=vpCameraParameters())
void computeInteractionMatrixAndResidu(const vpHomogeneousMatrix &cMc0, vpColVector &_R, vpMatrix &_J)
void setName(const std::string &circle_name)
std::string getName() const
double getQuality() const
Get the parameter characterizing the minimal accepted quality of image corners.
void changeFrame(const vpHomogeneousMatrix &cMo)
void displayPrimitive(const vpImage< unsigned char > &_I)
void setWindowSize(const unsigned int &w)
void diag(const double &val=1.0)
bool useScanLine
Use Scanline for visibility tests.
vpVelocityTwistMatrix buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
double minLineLengthThresholdGeneral
Minimum line length threshold for LOD mode (general setting)
void setAngleDisappear(const double &adisappear)
double getMinPolygonAreaThreshold() const
vpColVector m_error
Error s-s*.
void setTrackerId(int tid)
Does nothing. Just here for compat with previous releases that use OpenCV C api to do the tracking...
unsigned int maskBorder
Erosion of the mask.
Generic class defining intrinsic camera parameters.
int getBlockSize() const
Get the size of the averaging block used to track the features.
Implementation of a polygon of the model containing points of interest. It is used by the model-based...
void getFeature(const int &index, int &id, float &x, float &y) const
std::map< int, vpImagePoint > getKltImagePointsWithId() const
unsigned int getInitialNumberPoint() const
void extract(vpRotationMatrix &R) const
void setHarrisParam(const double &hp)
bool hasEnoughPoints() const
Implementation of a velocity twist matrix and operations on such kind of matrices.
vpMbtOptimizationMethod m_optimizationMethod
Optimization method used.
unsigned int getRows() const
Return the number of rows of the 2D array.
void setMinDistance(const double &mD)
void initTracking(const cv::Mat &I, const cv::Mat &mask=cv::Mat())
double angleAppears
Angle used to detect a face appearance.
vpKltOpencv tracker
Points tracker.
void setInitialGuess(const std::vector< cv::Point2f > &guess_pts)
virtual bool isVisible(const vpHomogeneousMatrix &cMo, const double alpha, const bool &modulo=false, const vpCameraParameters &cam=vpCameraParameters(), const vpImage< unsigned char > &I=vpImage< unsigned char >())
vpColVector getNormal() const
void setPyramidLevels(const int pyrMaxLevel)
std::list< vpMbtDistanceKltCylinder * > kltCylinders
bool useScanLine
Use scanline rendering.
std::map< int, vpImagePoint > & getCurrentPoints()
static double rad(double deg)
virtual void setMinLineLengthThresh(const double minLineLengthThresh, const std::string &name="")
void buildFrom(const vpPoint &p1, const vpPoint &p2, const double &r)
double threshold_outlier
Threshold below which the weight associated to a point to consider this one as an outlier...
vpMbHiddenFaces< vpMbtPolygon > * hiddenface
Pointer to the list of faces.
void preTracking(const vpImage< unsigned char > &I, unsigned int &nbInfos, unsigned int &nbFaceUsed)
cv::Mat cur
Temporary OpenCV image for fast conversion.
double lambda
The gain of the virtual visual servoing stage.
void display(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, const vpColor col, const unsigned int thickness=1, const bool displayFullModel=false)
double getMinLineLengthThreshold() const
void computeJTR(const vpMatrix &J, const vpColVector &R, vpColVector &JTR)
void setMaxFeatures(const unsigned int &mF)
void computeHomography(const vpHomogeneousMatrix &_cTc0, vpHomography &cHc0)
virtual void initCircle(const vpPoint &, const vpPoint &, const vpPoint &, const double, const int, const std::string &name="")
void setWindowSize(const int winSize)
double getQuality() const
std::list< vpMbtDistanceCircle * > circles_disp
Vector of the circles used here only to display the full model.
double minPolygonAreaThresholdGeneral
Minimum polygon area threshold for LOD mode (general setting)
static double deg(double rad)
virtual void setCameraParameters(const vpCameraParameters &_cam)
bool displayFeatures
If true, the features are displayed.
virtual void loadModel(const char *modelFile, const bool verbose=false)
void setCameraParameters(const vpCameraParameters &cam)
bool ogreShowConfigDialog
bool applyLodSettingInConfig
True if the CAO model is loaded before the call to loadConfigFile, (deduced by the number of polygons...
Implementation of column vector and the associated operations.
void setAngleAppear(const double &aappear)
Wrapper for the KLT (Kanade-Lucas-Tomasi) feature tracker implemented in OpenCV.
vpHomogeneousMatrix inverse() const
void setBlockSize(const int blockSize)
static vpHomogeneousMatrix direct(const vpColVector &v)
int getNbFeatures() const
Get the number of current features.
Contains an M-Estimator and various influence function.
double angleDisappears
Angle used to detect a face disappearance.
virtual unsigned int getNbPolygon() const
virtual void initFaceFromLines(vpMbtPolygon &polygon)
vpMbtPolygon * polygon
Pointer to the polygon that define a face.
unsigned int getHeight() const
unsigned int getNbPoint() const
vpMatrix pseudoInverse(double svThreshold=1e-6) const
Compute the pseudo inverse of the matrix using the SVD.
virtual void setClipping(const unsigned int &flags)
virtual void init(const vpImage< unsigned char > &I)
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
void setUseHarris(const int useHarrisDetector)
unsigned int getCurrentNumberPoints() const
void setBlockSize(const unsigned int &bs)
This class defines the container for a plane geometrical structure.
unsigned int clippingFlag
Flags specifying which clipping to used.
double getMinDistance() const
Get the minimal Euclidean distance between detected corners during initialization.
void displayOgre(const vpHomogeneousMatrix &cMo)
double getAngleAppear() const
unsigned int getCurrentNumberPoints() const
void setThreshold(const double noise_threshold)
void updateMask(cv::Mat &mask, unsigned char _nb=255, unsigned int _shiftBorder=0)
virtual void setFarClippingDistance(const double &dist)
double getMinDistance() const
bool getFovClipping() const
void setIteration(const unsigned int iter)
Set iteration.
bool useLodGeneral
True if LOD mode is enabled.
void computeScanLineRender(const vpCameraParameters &cam, const unsigned int &w, const unsigned int &h)
void computeVVS(const unsigned int &nbInfos, vpColVector &w)
Class that consider the case of a translation vector.
bool isoJoIdentity
Boolean to know if oJo is identity (for fast computation)
void setMaskBorder(const unsigned int &mb)
void computeInteractionMatrixAndResidu(vpColVector &_R, vpMatrix &_J)
vpHomogeneousMatrix c0Mo
Initial pose.
int getWindowSize() const
Get the window size used to refine the corner locations.
void track(const cv::Mat &I)
void display(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, const vpColor col, const unsigned int thickness=1, const bool displayFullModel=false)
unsigned int getPyramidLevels() const
virtual void display(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, const vpColor &col, const unsigned int thickness=1, const bool displayFullModel=false)
virtual void setPose(const vpImage< unsigned char > &I, const vpHomogeneousMatrix &cdMo)
bool useScanLine
Use scanline rendering.
void updateMask(cv::Mat &mask, unsigned char _nb=255, unsigned int _shiftBorder=0)
void resize(const unsigned int i, const bool flagNullify=true)
vpColVector m_w
Weights used in the robust scheme.
virtual void setLod(const bool useLod, const std::string &name="")
virtual void setNearClippingDistance(const double &dist)
void computeFov(const unsigned int &w, const unsigned int &h)