Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found

Target

Select target project
  • ped-dyn-emp/petrack
1 result
Show changes
Commits on Source (23)
......@@ -58,6 +58,8 @@ public:
bool getTrackRoiFix();
void setTrackRoiFix(bool b);
bool getAdaptiveLevel();
int getFilterBorderSize();
double getCalibFxValue();
......
......@@ -541,6 +541,7 @@ private:
bool tryMergeTrajectories(const TrackPoint& v, size_t i, int frame);
void trackFeaturePointsLK(int level);
void trackFeaturePointsLK(int level, bool adaptive);
void refineViaColorPointLK(int level, float errorScale);
void useBackgroundFilter(QList<int>& trjToDel, BackgroundFilter *bgFilter);
void refineViaNearDarkPoint();
......
......@@ -252,6 +252,13 @@ void Control::setTrackRoiFix(bool b)
//---------------------------------------
bool Control::getAdaptiveLevel()
{
return adaptiveLevel->isChecked();
}
//---------------------------------------
int Control::getFilterBorderSize()
{
return filterBorderParamSize->value();
......@@ -2488,6 +2495,7 @@ void Control::setXml(QDomElement &elem)
subSubElem.setAttribute("LEVELS", trackRegionLevels->value());
subSubElem.setAttribute("MAX_ERROR", trackErrorExponent->value());
subSubElem.setAttribute("SHOW", trackShowSearchSize->isChecked());
subSubElem.setAttribute("ADAPTIVE", adaptiveLevel->isChecked());
subElem.appendChild(subSubElem);
subSubElem = (elem.ownerDocument()).createElement("PATH");
......@@ -3095,6 +3103,8 @@ void Control::getXml(QDomElement &elem)
trackErrorExponent->setValue(subSubElem.attribute("MAX_ERROR").toInt());
if (subSubElem.hasAttribute("SHOW"))
trackShowSearchSize->setCheckState(subSubElem.attribute("SHOW").toInt() ? Qt::Checked : Qt::Unchecked);
if(subSubElem.hasAttribute("ADAPTIVE"))
adaptiveLevel->setCheckState(subSubElem.attribute("ADAPTIVE").toInt() ? Qt::Checked : Qt::Unchecked);
}
else if (subSubElem.tagName() == "PATH")
{
......
......@@ -4057,7 +4057,7 @@ QSet<int> Petrack::getOnlyVisible()
if(!ok)
debout << "Warning: error while reading showOnlyVisible list from input line!" << endl;
}
return onlyVisible;//QSet<int>() << mControlWidget->trackShowOnlyNr->text().split(",").toSet(); //in anzeige wird ab 1 gezaehlt, in datenstruktur ab 0
return onlyVisible; //in anzeige wird ab 1 gezaehlt, in datenstruktur ab 0
}else // if(ControlWidget->trackShowOnly->checkState() == Qt::Checked) //
{
......
......@@ -1530,7 +1530,9 @@ int Tracker::track(Mat &img,Rect &rect, int frame, bool reTrack, int reQual, int
debout << "Warning: linear interpolation of skipped frames which are not already tracked (" << mPrevFrame << " to " << frame << ")." << endl; // will be done in insertFeaturePoints
}
trackFeaturePointsLK(level);
trackFeaturePointsLK(level, mMainWindow->getControlWidget()->getAdaptiveLevel());
// TODO Split up refineViaColorPointLK as well...
refineViaColorPointLK(level, errorScale);
BackgroundFilter *bgFilter = mMainWindow->getBackgroundFilter();
......@@ -1547,54 +1549,6 @@ int Tracker::track(Mat &img,Rect &rect, int frame, bool reTrack, int reQual, int
{
refineViaNearDarkPoint();
}
// NOTE Following comment can probably be deleted, quite old code -> commented out for long time
/*
// bei noch schlechteren punkten zweite strategie
for (i = 0; i < count; ++i)
if ((mTrackError[i] > MAX_TRACK_ERROR) || (mStatus[i] == 0))
againNumber++;
// wenn trackpoint zu grossen fehler haben oder gar nicht berechnet werden konnten,
// dann wird mit dem zehnfachen der winSize (30) eine wiederholung durchgefuehrt
if (againNumber)
{
// mgl besser einmal anlegen und immer wieder benutzen
CvPoint2D32f* againPrevFeaturePoints = (CvPoint2D32f*) cvAlloc(againNumber*sizeof(CvPoint2D32f)); //points[0]
CvPoint2D32f* againFeaturePoints = (CvPoint2D32f*) cvAlloc(againNumber*sizeof(CvPoint2D32f)); //points[1]
char* againStatus = (char*) cvAlloc(againNumber);
//againTrackError = (float*) cvAlloc(againNumber*sizeof(float));
j=0;
for (i = 0; i < count; ++i)
if ((mTrackError[i] > MAX_TRACK_ERROR) || (mStatus[i] == 0))
{
againPrevFeaturePoints[j] = mPrevFeaturePoints[i];
againFeaturePoints[j] = mFeaturePoints[i];
againStatus[j] = 0;
j++;
}
cvCalcOpticalFlowPyrLK(mPrevGrey, mGrey, mPrevPyramid, mPyramid,
againPrevFeaturePoints, againFeaturePoints, againNumber, cvSize(winSize*10, winSize*10), level, againStatus, NULL,
cvTermCriteria(CV_TERMCRIT_ITER|CV_TERMCRIT_EPS, 20, 0.03), CV_LKFLOW_PYR_A_READY|CV_LKFLOW_PYR_B_READY);
j=0;
for (i = 0; i < count; ++i)
if ((mTrackError[i] > MAX_TRACK_ERROR) || (mStatus[i] == 0))
{
Vec2F v = Vec2F(mFeaturePoints+i);
Vec2F w = Vec2F(againFeaturePoints+j);
debout << "--------------" << i << ", " << j << ": " << (int) againStatus[j] << " " << v.x() << " " <<v.y() << " " <<w.x() << " " << w.y() << " error: " << mTrackError[i] <<endl;
if ((againStatus[j] != 0))
{
mStatus[i] = 1;
mFeaturePoints[i] = againFeaturePoints[j];
// im anschluss koennte die position noch optimiert werden (dunkelster punkt in umgebung)
}
j++;
}
cvFree(&againPrevFeaturePoints);
cvFree(&againFeaturePoints);
cvFree(&againStatus);
}
*/
inserted = insertFeaturePoints(frame, numOfPeopleToTrack, img, borderSize, errorScale);
}
......@@ -1641,43 +1595,71 @@ void Tracker::preCalculateImagePyramids(int level)
cv::buildOpticalFlowPyramid(mGrey, mCurrentPyr, cv::Size(maxWinSize,maxWinSize), level);
}
/**
* @brief Tracks the mPrevFeaturePoints with Lucas-Kanade
* @brief Tracks the mPrevFeaturePoints with Lucas-Kanade (optional adaptive pyramid level)
*
* This function tracks all points in mPrevFeaturePoints via Lucas-Kanade. Each person is
* tracked with a different winSize according to the size of the head.
* tracked with a different winSize according to the size of the head. Optionally the
* pyramid level can lowered, if the person could not be properly tracked and adaptive is
* set to true. This was added because from OpenCV 3 onwards the tracking failed in cases,
* where it should work. A suspicion: Happens when there is no unique point in the following
* frame, because of every pixel having the exact same grey level in the smalles pyramid scale.
*
* @param level Maximum level to track with
* @param numOfPeopleToTrack Number of people to be tracked
* @see Tracker::calcPrevFeaturePoints
* @param level Maximum pyramid level to track with
* @param adaptive indicates if pyramid level should be lowered after unsuccessful tracking attempt
*/
void Tracker::trackFeaturePointsLK(int level)
void Tracker::trackFeaturePointsLK(int level, bool adaptive)
{
int winSize;
for (size_t i = 0; i < mPrevFeaturePointsIdx.size(); ++i)
const size_t numOfPeople = mPrevFeaturePointsIdx.size();
mFeaturePoints.resize(numOfPeople);
mStatus.resize(numOfPeople);
mTrackError.resize(numOfPeople);
vector<uchar> localStatus;
vector<float> localTrackError;
for(size_t i = 0; i < numOfPeople; ++i)
{
// das Durchlaufen der level bis 0 fuer den Fall, dass kein Tracking moeglich ist (mStatus ==0)
// ist erst ab opencv 3 hinzugenommen worden, da es manchmal zum abbruch kam, obwohl ein tracking moeglich sein sollte
// ein verdacht: wenn sich in folgebildern kein eindeutiger punkt ergibt, da in der kleinsten pyr stufe rundherum die exakt gleiche farbe/graustufe vorherscht
int l = level;
int l = level;
int winSize = 0;
do
{
if(l < level)
{
debout << "Warning: try tracking person " << mPrevFeaturePointsIdx[i] << " with pyramid level " << l
<< "!" << endl;
}
winSize = mMainWindow->winSize(nullptr, mPrevFeaturePointsIdx[i], mPrevFrame, l);
if (winSize < MIN_WIN_SIZE)
if(winSize < MIN_WIN_SIZE)
{
winSize = MIN_WIN_SIZE;
debout << "Warning: set search region to the minimum size of "<<MIN_WIN_SIZE<<" for person " << mPrevFeaturePointsIdx[i] << "!" << endl;
debout << "Warning: set search region to the minimum size of " << MIN_WIN_SIZE << " for person "
<< mPrevFeaturePointsIdx[i] << "!" << endl;
}
if (l < level)
debout << "Warning: try tracking person " /*<< mPrevFeaturePointsIdx[i]*/ << " with pyramid level " << l<<"!" << endl;
cv::calcOpticalFlowPyrLK(mPrevPyr,mCurrentPyr,/*points[0]*/mPrevFeaturePoints,/*points[1]*/mFeaturePoints,mStatus,mTrackError,Size(winSize,winSize),l,mTermCriteria);
} while(mStatus[i] == 0 && (l--) > 0);
mTrackError[i] = mTrackError[i]*10.F/winSize;
vector<cv::Point2f> prevFeaturePoint{mPrevFeaturePoints[i]};
vector<cv::Point2f> nextFeaturePoint{};
localStatus.clear();
localTrackError.clear();
cv::calcOpticalFlowPyrLK(
mPrevPyr,
mCurrentPyr,
prevFeaturePoint,
nextFeaturePoint,
localStatus,
localTrackError,
Size(winSize, winSize),
l,
mTermCriteria);
mFeaturePoints[i] = nextFeaturePoint[0];
mTrackError[i] = localTrackError[0] * 10.F / winSize;
} while(adaptive && localStatus[0] == 0 && (l--) > 0);
mStatus[i] = localStatus[0];
}
}
......
<?xml version="1.0" ?>
<?xml version="1.0" encoding="UTF-8"?>
<!DOCTYPE PETRACK>
<PETRACK VERSION="0.8">
<MAIN SRC="P:/ped/regressiontest_petrack/acceptedTruth/input\multicolor.mp4;multicolor.mp4" STATUS_HEIGHT="0"/>
<CONTROL TAB="0">
<MAIN SRC="C:/Users/Deniz/Documents/petrack/tests/regression_test/data/multicolor.mp4;multicolor.mp4" STATUS_HEIGHT="0"/>
<CONTROL TAB="2">
<CALIBRATION>
<BRIGHTNESS ENABLED="0" VALUE="0"/>
<CONTRAST ENABLED="0" VALUE="0"/>
<BORDER COLOR="#000000" ENABLED="1" VALUE="91"/>
<SWAP VERTICALLY="0" HORIZONTALLY="0" ENABLED="0"/>
<BG_SUB UPDATE="0" SHOW="0" FILE="" DELETE_NUMBER="3" ENABLED="0" DELETE="1"/>
<PATTERN SQUARE_SIZE="4.6" BOARD_SIZE_X="6" BOARD_SIZE_Y="8"/>
<INTRINSIC_PARAMETERS TY="5.5e-005" CALIB_FILES="P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_00_01_21.Standbild001.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_00_04_20.Standbild002.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_00_06_13.Standbild003.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_00_08_15.Standbild004.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_00_13_22.Standbild005.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_00_15_12.Standbild006.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_00_21_16.Standbild007.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_00_23_22.Standbild008.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_00_27_17.Standbild009.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_00_33_19.Standbild010.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_00_36_05.Standbild011.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_00_41_19.Standbild012.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_00_44_15.Standbild013.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_00_47_03.Standbild014.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_00_51_03.Standbild015.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_00_52_03.Standbild016.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_01_00_08.Standbild017.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_01_02_08.Standbild018.png" K5="0" QUAD_ASPECT_RATIO="0" FIX_CENTER="0" R4="0.093288" R2="-0.276626" ENABLED="1" TANG_DIST="1" K6="0" R6="-0.01423" CY="880.72" TX="-0.000247" K4="0" FX="842.5700000000001" FY="842.6900000000001" CX="1134.04"/>
<EXTRINSIC_PARAMETERS COORD3D_TRANS_X="0" ALTITUDE="535" COORD_DIMENSION="0" COORD3D_TRANS_Z="0" ROTATE="0" COORD3D_SWAP_X="0" COORD3D_SWAP_Y="1" SCALE="100" TRANS_X="0" EXTR_ROT_1="-2.192" SHOW="0" EXTR_ROT_3="0.016" TRANS_Y="0" USE_INTRINSIC_CENTER="0" COORD3D_SWAP_Z="0" EXTR_ROT_2="-2.183" EXTERNAL_CALIB_FILE="P:/ped/experiments/2017.06.10_Wermelskirchen_SiME/raw/Samstag/gopro3/extr_calib/extrinsic_calib_13p.3dc;../../../experiments/2017.06.10_Wermelskirchen_SiME/raw/Samstag/gopro3/extr_calib/extrinsic_calib_13p.3dc" SHOW_CALIB_POINTS="0" EXTR_TRANS_2="13.741" EXTR_TRANS_3="-626.842" COORD3D_AXIS_LEN="200" UNIT="100" COORD3D_TRANS_Y="0" FIX="0" EXTR_TRANS_1="-1043.473"/>
<ALIGNMENT_GRID SCALE="100" SHOW="0" ROTATE="0" GRID3D_TRANS_Y="34" GRID3D_TRANS_Z="0" GRID3D_TRANS_X="91" GRID_DIMENSION="0" GRID3D_RESOLUTION="100" FIX="0" TRANS_Y="0" TRANS_X="0"/>
<SWAP ENABLED="0" HORIZONTALLY="0" VERTICALLY="0"/>
<BG_SUB DELETE="1" DELETE_NUMBER="3" ENABLED="0" FILE="" SHOW="0" UPDATE="0"/>
<PATTERN BOARD_SIZE_X="6" BOARD_SIZE_Y="8" SQUARE_SIZE="4.5999999"/>
<INTRINSIC_PARAMETERS CALIB_FILES="P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_00_01_21.Standbild001.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_00_04_20.Standbild002.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_00_06_13.Standbild003.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_00_08_15.Standbild004.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_00_13_22.Standbild005.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_00_15_12.Standbild006.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_00_21_16.Standbild007.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_00_23_22.Standbild008.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_00_27_17.Standbild009.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_00_33_19.Standbild010.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_00_36_05.Standbild011.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_00_41_19.Standbild012.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_00_44_15.Standbild013.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_00_47_03.Standbild014.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_00_51_03.Standbild015.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_00_52_03.Standbild016.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_01_00_08.Standbild017.png, P:/ped/cameras/gopro_3/calibration/6x8_4.6cm/calib_frames/GOPR3527.00_01_02_08.Standbild018.png" CX="1134.04" CY="880.72000000000003" ENABLED="1" FIX_CENTER="0" FX="842.57000000000005" FY="842.69000000000005" K4="0" K5="0" K6="0" QUAD_ASPECT_RATIO="0" R2="-0.27662599999999998" R4="0.093287999999999996" R6="-0.01423" TANG_DIST="1" TX="-0.00024699999999999999" TY="5.5000000000000002e-05"/>
<EXTRINSIC_PARAMETERS ALTITUDE="535" COORD3D_AXIS_LEN="200" COORD3D_SWAP_X="0" COORD3D_SWAP_Y="1" COORD3D_SWAP_Z="0" COORD3D_TRANS_X="0" COORD3D_TRANS_Y="0" COORD3D_TRANS_Z="0" COORD_DIMENSION="0" EXTERNAL_CALIB_FILE="" EXTR_ROT_1="-2.1920000000000002" EXTR_ROT_2="-2.1829999999999998" EXTR_ROT_3="0.016" EXTR_TRANS_1="-1043.473" EXTR_TRANS_2="13.741" EXTR_TRANS_3="-626.84199999999998" FIX="0" ROTATE="0" SCALE="100" SHOW="0" SHOW_CALIB_POINTS="0" TRANS_X="0" TRANS_Y="0" UNIT="100" USE_INTRINSIC_CENTER="0"/>
<ALIGNMENT_GRID FIX="0" GRID3D_RESOLUTION="100" GRID3D_TRANS_X="91" GRID3D_TRANS_Y="34" GRID3D_TRANS_Z="0" GRID_DIMENSION="0" ROTATE="0" SCALE="100" SHOW="0" TRANS_X="0" TRANS_Y="0"/>
</CALIBRATION>
<RECOGNITION>
<PERFORM METHOD="5" ENABLED="0" STEP="1"/>
<REGION_OF_INTEREST WIDTH="1971" X="-12" HEIGHT="1654" SHOW="0" Y="-129" FIX="1"/>
<MARKER IGNORE_WITHOUT="1" BRIGHTNESS="50"/>
<SIZE_COLOR X="0" MAP_NUMBER="4" SHOW="1" Y="1" AUTO_WB="0" MODEL="0" SYMBOL_SIZE="10" Z="255" DEFAULT_HEIGHT="174.1" GREY_LEVEL="50">
<MAP WIDTH="330" X="26" COLORED="1" FROM_SAT="122" HEIGHT="133" Y="122" TO_VAL="255" TO_SAT="255" MAP_HEIGHT="158" TO_HUE="26" INV_HUE="1" FROM_HUE="356" FROM_VAL="165"/>
<MAP WIDTH="32" X="57" COLORED="1" FROM_SAT="101" HEIGHT="154" Y="101" TO_VAL="255" TO_SAT="255" MAP_HEIGHT="168" TO_HUE="89" INV_HUE="0" FROM_HUE="57" FROM_VAL="166"/>
<MAP WIDTH="47" X="94" COLORED="1" FROM_SAT="62" HEIGHT="193" Y="62" TO_VAL="255" TO_SAT="255" MAP_HEIGHT="179" TO_HUE="141" INV_HUE="0" FROM_HUE="94" FROM_VAL="147"/>
<MAP WIDTH="29" X="196" COLORED="1" FROM_SAT="134" HEIGHT="121" Y="134" TO_VAL="255" TO_SAT="255" MAP_HEIGHT="192" TO_HUE="196" INV_HUE="0" FROM_HUE="225" FROM_VAL="154"/>
<MAP WIDTH="45" X="295" COLORED="1" FROM_SAT="103" HEIGHT="152" Y="103" TO_VAL="255" TO_SAT="255" MAP_HEIGHT="146" TO_HUE="295" INV_HUE="0" FROM_HUE="340" FROM_VAL="168"/>
<PERFORM ENABLED="0" METHOD="5" STEP="1"/>
<REGION_OF_INTEREST FIX="1" HEIGHT="1654" SHOW="0" WIDTH="1971" X="-12" Y="-129"/>
<MARKER BRIGHTNESS="50" IGNORE_WITHOUT="1"/>
<SIZE_COLOR AUTO_WB="0" DEFAULT_HEIGHT="174.09999999999999" GREY_LEVEL="50" MAP_NUMBER="4" MODEL="0" SHOW="1" SYMBOL_SIZE="10" X="0" Y="1" Z="255">
<MAP COLORED="1" FROM_HUE="356" FROM_SAT="122" FROM_VAL="165" HEIGHT="133" INV_HUE="1" MAP_HEIGHT="158" TO_HUE="26" TO_SAT="255" TO_VAL="255" WIDTH="330" X="26" Y="122"/>
<MAP COLORED="1" FROM_HUE="57" FROM_SAT="101" FROM_VAL="166" HEIGHT="154" INV_HUE="0" MAP_HEIGHT="168" TO_HUE="89" TO_SAT="255" TO_VAL="255" WIDTH="32" X="57" Y="101"/>
<MAP COLORED="1" FROM_HUE="94" FROM_SAT="62" FROM_VAL="147" HEIGHT="193" INV_HUE="0" MAP_HEIGHT="179" TO_HUE="141" TO_SAT="255" TO_VAL="255" WIDTH="47" X="94" Y="62"/>
<MAP COLORED="1" FROM_HUE="225" FROM_SAT="134" FROM_VAL="154" HEIGHT="121" INV_HUE="0" MAP_HEIGHT="192" TO_HUE="196" TO_SAT="255" TO_VAL="255" WIDTH="29" X="196" Y="134"/>
<MAP COLORED="1" FROM_HUE="340" FROM_SAT="103" FROM_VAL="168" HEIGHT="152" INV_HUE="0" MAP_HEIGHT="146" TO_HUE="295" TO_SAT="255" TO_VAL="255" WIDTH="45" X="295" Y="103"/>
</SIZE_COLOR>
</RECOGNITION>
<TRACKING>
<ONLINE_CALCULATION ENABLED="0"/>
<REPEAT_BELOW QUALITY="50" ENABLED="1"/>
<REPEAT_BELOW ENABLED="1" QUALITY="50"/>
<EXTRAPOLATION ENABLED="1"/>
<MERGE ENABLED="0"/>
<ONLY_VISIBLE ENABLED="1"/>
<REGION_OF_INTEREST WIDTH="2046" X="-48" HEIGHT="1728" SHOW="0" Y="-164" FIX="1"/>
<REGION_OF_INTEREST FIX="1" HEIGHT="1728" SHOW="0" WIDTH="2046" X="-48" Y="-164"/>
<SEARCH_MISSING_FRAMES ENABLED="0"/>
<RECALCULATE_MEDIAN_HEIGHT ENABLED="0"/>
<ALLOW_ALTERNATE_HEIGHT ENABLED="0"/>
......@@ -48,39 +48,40 @@
<TEST_VELOCITY ENABLED="1"/>
<TEST_INSIDE ENABLED="1"/>
<TEST_LENGTH ENABLED="1"/>
<SEARCH_REGION SCALE="11" MAX_ERROR="0" SHOW="0" LEVELS="1"/>
<PATH GROUND_PATH_SIZE="1" NUMBER_BOLD="1" POINTS_SIZE="7" POINTS_COLORED="1" ONLY_PEOPLE_NR_LIST="88" NUMBER_SIZE="14" ONLY_VISIBLE="0" SHOW="1" COLLECTIVE_COLOR_SIZE="11" SHOW_GROUND_PATH="0" BEFORE="15" TRACK_PATH_COLOR="#ff0000" SHOW_NUMBER="1" SHOW_PATH="1" AFTER="15" CURRENT_POINT_SIZE="60" SHOW_POINTS="0" SHOW_GROUND_POSITION="0" ONLY_PEOPLE_LIST="0" SHOW_COLLECTIVE_COLOR="1" PATH_SIZE="2" HEAD_SIZE="1" TRACK_GROUND_PATH_COLOR="#00ff00" SHOW_COLOR_MARKER="1" ONLY_PEOPLE="1" ONLY_PEOPLE_NR="88" FIX="0" COLOR_MARKER_SIZE="14" SHOW_CURRENT_POINT="1" GROUND_POSITION_SIZE="1"/>
<SEARCH_REGION ADAPTIVE="1" LEVELS="2" MAX_ERROR="0" SCALE="14" SHOW="0"/>
<PATH AFTER="15" BEFORE="15" COLLECTIVE_COLOR_SIZE="11" COLOR_MARKER_SIZE="14" CURRENT_POINT_SIZE="7" FIX="0" GROUND_PATH_SIZE="1" GROUND_POSITION_SIZE="1" HEAD_SIZE="0" NUMBER_BOLD="1" NUMBER_SIZE="14" ONLY_PEOPLE="1" ONLY_PEOPLE_LIST="0" ONLY_PEOPLE_NR="1" ONLY_PEOPLE_NR_LIST="1" ONLY_VISIBLE="0" PATH_SIZE="2" POINTS_COLORED="1" POINTS_SIZE="7" SHOW="1" SHOW_COLLECTIVE_COLOR="1" SHOW_COLOR_MARKER="1" SHOW_CURRENT_POINT="1" SHOW_GROUND_PATH="0" SHOW_GROUND_POSITION="0" SHOW_NUMBER="1" SHOW_PATH="1" SHOW_POINTS="0" TRACK_GROUND_PATH_COLOR="#00ff00" TRACK_PATH_COLOR="#ff0000"/>
</TRACKING>
<ANALYSIS>
<SEARCH_MISSING_FRAMES ENABLED="1"/>
<MARK_ACTUAL ENABLED="0"/>
<CALCULATION STEP_SIZE="25" REVERSE="0" SHOW_VORONOI="0" ABSOLUTE="0" CONSIDER_X="0" CONSIDER_Y="1"/>
<CALCULATION ABSOLUTE="0" CONSIDER_X="0" CONSIDER_Y="1" REVERSE="0" SHOW_VORONOI="0" STEP_SIZE="25"/>
</ANALYSIS>
</CONTROL>
<STEREO>
<DISPARITY COLOR="0" SHOW="0" OPACITY="100" HIDE_INVALID="1" ALGO="0">
<DISPARITY ALGO="0" COLOR="0" HIDE_INVALID="1" OPACITY="100" SHOW="0">
<VALUES MAX="100" MIN="0"/>
<MASK SIZE="7" EDGE_SIZE="5" USE_EDGE="0"/>
<USE HEIGHT="0" HEIGHT_EVER="1" CALIB_CENTER="1" EXPORT="0" RECO="0"/>
<MASK EDGE_SIZE="5" SIZE="7" USE_EDGE="0"/>
<USE CALIB_CENTER="1" EXPORT="0" HEIGHT="0" HEIGHT_EVER="1" RECO="0"/>
</DISPARITY>
</STEREO>
<COLOR_MARKER>
<MASK MASK="1" SHOW="0" OPACITY="100"/>
<MASK MASK="1" OPACITY="100" SHOW="0"/>
<FROM_COLOR HUE="0" SATURATION="0" VALUE="0"/>
<TO_COLOR HUE="359" SATURATION="255" VALUE="255"/>
<PARAM CLOSE_USED="1" INVERS_HUE="0" MAX_AREA="5000" CLOSE_RADIUS="5" OPEN_RADIUS="5" OPEN_USED="1" MIN_AREA="1000" MAX_RATIO="2"/>
<PARAM CLOSE_RADIUS="5" CLOSE_USED="1" INVERS_HUE="0" MAX_AREA="5000" MAX_RATIO="2" MIN_AREA="1000" OPEN_RADIUS="5" OPEN_USED="1"/>
</COLOR_MARKER>
<CODE_MARKER>
<DICTIONARY ID="16"/>
<PARAM ADAPTIVE_THRESH_WIN_SIZE_MIN="3" CORNER_REFINEMENT="0" ADAPTIVE_THRESH_WIN_SIZE_STEP="10" MIN_MARKER_DISTANCE="0.05" MIN_OTSU_STD_DEV="5" CORNER_REFINEMENT_MIN_ACCURACY="0.1" MIN_CORNER_DISTANCE="0.05" MARKER_BORDER_BITS="1" ADAPTIVE_THRESH_WIN_SIZE_MAX="23" CORNER_REFINEMENT_MAX_ITERATIONS="30" ERROR_CORRECTION_RATE="0.6" SHOW_DETECTED_CANDIDATES="0" MAX_ERRONEOUS_BITS_IN_BORDER_RATE="0.35" PERSPECTIVE_REMOVE_IGNORED_MARGIN_PER_CELL="0.13" MIN_MARKER_PERIMETER="5" ADAPTIVE_THRESH_CONSTANT="7" CORNER_REFINEMENT_WIN_SIZE="5" PERSPECTIVE_REMOVE_PIXEL_PER_CELL="4" MAX_RATIO_ERROR="0.03" MIN_DISTANCE_TO_BORDER="3" MAX_MARKER_PERIMETER="15"/>
<PARAM ADAPTIVE_THRESH_CONSTANT="7" ADAPTIVE_THRESH_WIN_SIZE_MAX="23" ADAPTIVE_THRESH_WIN_SIZE_MIN="3" ADAPTIVE_THRESH_WIN_SIZE_STEP="10" CORNER_REFINEMENT="0" CORNER_REFINEMENT_MAX_ITERATIONS="30" CORNER_REFINEMENT_MIN_ACCURACY="0.10000000000000001" CORNER_REFINEMENT_WIN_SIZE="5" ERROR_CORRECTION_RATE="0.59999999999999998" MARKER_BORDER_BITS="1" MAX_ERRONEOUS_BITS_IN_BORDER_RATE="0.34999999999999998" MAX_MARKER_PERIMETER="15" MAX_RATIO_ERROR="0.029999999999999999" MIN_CORNER_DISTANCE="0.050000000000000003" MIN_DISTANCE_TO_BORDER="3" MIN_MARKER_DISTANCE="0.050000000000000003" MIN_MARKER_PERIMETER="5" MIN_OTSU_STD_DEV="5" PERSPECTIVE_REMOVE_IGNORED_MARGIN_PER_CELL="0.13" PERSPECTIVE_REMOVE_PIXEL_PER_CELL="4" SHOW_DETECTED_CANDIDATES="0"/>
</CODE_MARKER>
<MULTI_COLOR_MARKER>
<BLACK_DOT IGNORE_WITHOUT="1" RESTRICT_POSITION="0" USE="0" SIZE="5" USE_COLOR="0"/>
<AUTO_CORRECT USE="1" ONLY_EXPORT="0"/>
<MASK MASK="1" SHOW="0" OPACITY="50"/>
<PARAM CLOSE_USED="1" MAX_AREA="1500" USE_HEAD_SIZE="0" CLOSE_RADIUS="3" OPEN_RADIUS="3" OPEN_USED="1" MIN_AREA="230" MAX_RATIO="2"/>
<BLACK_DOT IGNORE_WITHOUT="1" RESTRICT_POSITION="0" SIZE="5" USE="0" USE_COLOR="0"/>
<CODE_MARKER USE="0"/>
<AUTO_CORRECT ONLY_EXPORT="0" USE="1"/>
<MASK MASK="1" OPACITY="50" SHOW="0"/>
<PARAM CLOSE_RADIUS="3" CLOSE_USED="1" MAX_AREA="1500" MAX_RATIO="2" MIN_AREA="230" OPEN_RADIUS="3" OPEN_USED="1" USE_HEAD_SIZE="0"/>
</MULTI_COLOR_MARKER>
<PLAYER SOURCE_FRAME_IN="0" FPS="25" SOURCE_FRAME_OUT="420" FRAME="0" PLAYER_SPEED_FIXED="1"/>
<VIEW OPENGL="0" SAVE_TRANSFORMED="0" CAMERA="2" HIDE_CONTROLS="0" TRANSFORMATION="209 0 0 0" ANTIALIAS="0"/>
<AUTO_TRACK OPTIMZE_COLOR="0" BACK_TRACK="1"/>
<PLAYER FPS="25" FRAME="0" PLAYER_SPEED_FIXED="1" SOURCE_FRAME_IN="0" SOURCE_FRAME_OUT="420"/>
<VIEW ANTIALIAS="0" CAMERA="2" HIDE_CONTROLS="0" OPENGL="0" SAVE_TRANSFORMED="0" TRANSFORMATION="340 0 2900 4914"/>
<AUTO_TRACK BACK_TRACK="1" OPTIMZE_COLOR="0"/>
</PETRACK>
......@@ -121,8 +121,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>342</width>
<height>1081</height>
<width>337</width>
<height>1028</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout_13">
......@@ -3211,8 +3211,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>342</width>
<height>876</height>
<width>337</width>
<height>874</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout_16">
......@@ -4447,8 +4447,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>342</width>
<height>863</height>
<width>337</width>
<height>843</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout_17">
......@@ -5407,17 +5407,31 @@
</layout>
</item>
<item>
<widget class="QCheckBox" name="trackShowSearchSize">
<property name="maximumSize">
<size>
<width>300</width>
<height>16777215</height>
</size>
</property>
<property name="text">
<string>show pyramidal search size</string>
</property>
</widget>
<layout class="QHBoxLayout" name="horizontalLayout_23">
<item>
<widget class="QCheckBox" name="trackShowSearchSize">
<property name="maximumSize">
<size>
<width>300</width>
<height>16777215</height>
</size>
</property>
<property name="text">
<string>show pyramidal search size</string>
</property>
</widget>
</item>
<item>
<widget class="QCheckBox" name="adaptiveLevel">
<property name="toolTip">
<string>When checked, failed attempts to track are repeated with a lower pyramid level. Mostly results in worse trajectories.</string>
</property>
<property name="text">
<string>adaptive level</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
......@@ -7199,8 +7213,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>356</width>
<height>557</height>
<width>354</width>
<height>558</height>
</rect>
</property>
<layout class="QVBoxLayout" name="verticalLayout_18">
......@@ -7457,7 +7471,6 @@
<tabstop>testVelocity</tabstop>
<tabstop>testInside</tabstop>
<tabstop>testLength</tabstop>
<tabstop>trackShowSearchSize</tabstop>
<tabstop>trackShow</tabstop>
<tabstop>trackFix</tabstop>
<tabstop>trackShowOnlyVisible</tabstop>
......