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 (22)
Showing with 1729 additions and 1532 deletions
......@@ -372,6 +372,7 @@ target_sources(petrack_core PRIVATE
include/moCapPersonMetadata.h
include/pMessageBox.h
include/moCapSelectionWidget.h
include/personStorage.h
)
target_sources(petrack_core PRIVATE
......@@ -431,6 +432,7 @@ target_sources(petrack_core PRIVATE
src/moCapPersonMetadata.cpp
src/pMessageBox.cpp
src/moCapSelectionWidget.cpp
src/personStorage.cpp
ui/about.ui
ui/codeMarker.ui
ui/colorMarker.ui
......
......@@ -34,26 +34,24 @@ class TrackerPlotItem;
class Control;
class Zoomer;
class RectPlotItem;
class PersonStorage;
class ViewColorPlotItem;
class TrackerPlotItem : public QwtPlotItem
{
public:
TrackerPlotItem();
void draw(QPainter *p, const QwtScaleMap &mapX, const QwtScaleMap &mapY, const QRectF &re) const;
void setPen(const QPen &pen);
void setModel(int model, int x, int y);
void setTracker(Tracker *tracker);
Tracker *getTracker();
void setPersonStorage(const PersonStorage *storage);
private:
Tracker *mTracker;
QPen mPen;
const PersonStorage *mPersonStorage = nullptr;
QPen mPen;
};
......@@ -163,7 +161,7 @@ public:
bool printDistribution() const;
void setControlWidget(Control *control);
void setTracker(Tracker *tracker);
void setPersonStorage(const PersonStorage *storage);
void setScale();
void generateImage();
......@@ -180,16 +178,17 @@ public:
inline RectPlotItem * getMapItem() const { return mRectItem; }
private:
double mSymbolSize;
double mXMax;
double mYMax;
Control * mControlWidget;
ImagePlotItem * mImageItem;
TrackerPlotItem * mTrackerItem;
RectPlotItem * mRectItem;
ViewColorPlotItem *mViewColorItem;
Zoomer * mZoomer;
int mGreyDiff;
const PersonStorage *mPersonStorage;
double mSymbolSize;
double mXMax;
double mYMax;
Control * mControlWidget;
ImagePlotItem * mImageItem;
TrackerPlotItem * mTrackerItem;
RectPlotItem * mRectItem;
ViewColorPlotItem * mViewColorItem;
Zoomer * mZoomer;
int mGreyDiff;
};
#endif
......@@ -21,13 +21,13 @@
#ifndef CONTROL_H
#define CONTROL_H
#include "petrack.h"
#include "recognition.h"
#include "ui_control.h"
#include <Qt>
#include <QtWidgets>
class Petrack;
class QGraphicsScene;
class QDomElement;
......
......@@ -30,7 +30,7 @@
class Petrack;
class Control;
class PersonStorage;
class ReprojectionError
{
......@@ -144,8 +144,9 @@ public:
class ExtrCalibration
{
private:
Petrack *mMainWindow;
Control *mControlWidget;
Petrack * mMainWindow;
Control * mControlWidget;
PersonStorage &mPersonStorage;
std::vector<cv::Point3f> points3D;
std::vector<cv::Point2f> points2D;
......@@ -164,7 +165,7 @@ private:
void init();
public:
ExtrCalibration();
ExtrCalibration(PersonStorage &storage);
~ExtrCalibration();
void setMainWindow(Petrack *mw);
bool isEmptyExtrCalibFile();
......
/*
* PeTrack - Software for tracking pedestrians movement in videos
* Copyright (C) 2010-2021 Forschungszentrum Jülich GmbH,
* Maik Boltes, Juliane Adrian, Ricardo Martin Brualla, Arne Graf, Paul Häger, Daniel Hillebrand,
* Deniz Kilic, Paul Lieberenz, Daniel Salden, Tobias Schrödter, Ann Katrin Seemann
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/
#ifndef PERSONSTORAGE_H
#define PERSONSTORAGE_H
#include "tracker.h"
#include <vector>
class Petrack;
class PersonStorage
{
public:
enum class Direction
{
Previous,
Following,
Whole
};
explicit PersonStorage(Petrack &mainWindow) : mMainWindow(mainWindow) {}
void splitPerson(size_t pers, int frame);
bool splitPersonAt(const Vec2F &p, int frame, const QSet<int> &onlyVisible);
bool delPointOf(int pers, int direction, int frame);
bool delPoint(const Vec2F &p, int direction, int frame, const QSet<int> &onlyVisible);
void delPointAll(Direction direction, int frame);
void delPointROI();
void delPointInsideROI();
bool editTrackPersonComment(const Vec2F &p, int frame, const QSet<int> &onlyVisible);
bool setTrackPersonHeight(const Vec2F &p, int frame, const QSet<int> &onlyVisible);
bool resetTrackPersonHeight(const Vec2F &p, int frame, QSet<int> onlyVisible);
size_t nbPersons() const { return mPersons.size(); }
const TrackPerson & at(size_t i) const { return mPersons.at(i); }
void addPerson(const TrackPerson &person) { mPersons.push_back(person); }
const std::vector<TrackPerson> &getPersons() const { return mPersons; }
// used for calculation of 3D point for all points in frame
// returns number of found points or -1 if no stereoContext available (also points without disp found are counted)
int calcPosition(int frame);
// true, if new traj is inserted with point p and initial frame frame
// p in pixel coord
// pers wird gesetzt, wenn existierender trackpoint einer person verschoben wird
bool addPoint(
TrackPoint & p,
int frame,
const QSet<int> & onlyVisible,
reco::RecognitionMethod method,
int * pers = nullptr);
// hier sollte direkt die farbe mit uebergeben werden
void addPoints(QList<TrackPoint> &pL, int frame, reco::RecognitionMethod method);
int visible(int frameNum) const;
int largestFirstFrame() const;
int largestLastFrame() const;
int smallestFirstFrame() const;
void recalcHeight(float altitude);
void clear() { mPersons.clear(); }
void smoothHeight(size_t i, int j);
void insertFeaturePoint(
size_t person,
int frame,
const TrackPoint &point,
int persNr,
bool extrapolate,
float z,
float height);
int merge(int pers1, int pers2);
void checkPlausibility(
QList<int> &pers,
QList<int> &frame,
bool testEqual = true,
bool testVelocity = true,
bool testInside = true,
bool testLength = true);
void optimizeColor();
// reset the height of all persons, but not the pos of the trackpoints
void resetHeight();
// reset the pos of the tzrackpoints, but not the heights
void resetPos();
// gibt groessenverteilung der personen auf stdout aus
// rueckgabewert false wenn keine hoeheninformationen in tracker datensatz vorliegt
bool printHeightDistribution();
void setMarkerHeights(const std::unordered_map<int, float> &heights);
void setMarkerIDs(const std::unordered_map<int, int> &markerIDs);
void purge(int frame);
void setNrInBg(size_t idx, int nr) { mPersons[idx].setNrInBg(nr); }
private:
std::vector<TrackPerson> mPersons;
Petrack & mMainWindow;
};
#endif // PERSONSTORAGE_H
......@@ -39,6 +39,7 @@
#include "extrCalibration.h"
#include "moCapController.h"
#include "moCapPerson.h"
#include "personStorage.h"
#include "recognition.h"
#include "swapFilter.h"
......@@ -149,7 +150,7 @@ public slots:
void setTrackPersonHeight(QPointF pos);
void resetTrackPersonHeight(QPointF pos);
void deleteTrackPoint(QPointF pos, int direction);
void deleteTrackPointAll(int direction);
void deleteTrackPointAll(PersonStorage::Direction direction);
void deleteTrackPointROI();
void deleteTrackPointInsideROI();
// void showContextMenu(QPointF pos);
......@@ -226,6 +227,8 @@ public:
inline QImage * getImage() { return mImage; }
inline cv::Mat getImg() { return mImg; }
inline cv::Mat getImageFiltered() { return mImgFiltered; }
inline PersonStorage & getPersonStorage() { return mPersonStorage; }
inline const PersonStorage & getPersonStorage() const { return mPersonStorage; }
inline Tracker * getTracker() { return mTracker; }
inline TrackerReal * getTrackerReal() { return mTrackerReal; }
inline ImageItem * getImageItem() { return mImageItem; }
......@@ -454,10 +457,11 @@ private:
reco::Recognizer mReco;
Tracker * mTracker;
TrackerReal *mTrackerReal;
double mHeadSize;
double mCmPerPixel;
PersonStorage mPersonStorage{*this};
Tracker * mTracker;
TrackerReal * mTrackerReal;
double mHeadSize;
double mCmPerPixel;
QDomDocument mDefaultSettings;
......
......@@ -218,7 +218,7 @@ signals:
// berechnet pixelverschiebung aufgrund von schraegsicht bei einem farbmarker
// Maik Dissertation Seite 138
// boxImageCentre ohne Border
Vec2F autoCorrectColorMarker(Vec2F &boxImageCentre, Control *controlWidget);
Vec2F autoCorrectColorMarker(const Vec2F &boxImageCentre, Control *controlWidget);
namespace detail
......
......@@ -21,13 +21,17 @@
#ifndef TRACKER_H
#define TRACKER_H
#include "petrack.h"
#include "recognition.h"
#include "vector.h"
#include <QColor>
#include <QList>
#include <QRegularExpression>
#include <QTextStream>
class PersonStorage;
class Petrack;
// war 1.5, aber bei bildauslassungen kann es ungewollt zuschlagen (bei 3 ist ein ausgelassener frame mgl, bei 2 wieder
// ein problem)
inline constexpr double EXTRAPOLATE_FACTOR = 3.;
......@@ -90,85 +94,9 @@ public:
};
inline QTextStream &operator>>(QTextStream &s, TrackPoint &tp)
{
double d;
Vec2F p;
Vec3F sp;
QColor col;
int qual;
int markerID;
s >> d;
tp.setX(d);
s >> d;
tp.setY(d);
if(Petrack::trcVersion > 1)
{
s >> d;
sp.setX(d);
s >> d;
sp.setY(d);
s >> d;
sp.setZ(d);
tp.setSp(sp);
}
s >> qual;
tp.setQual(qual);
s >> d;
p.setX(d);
s >> d;
p.setY(d);
tp.setColPoint(p);
s >> col;
tp.setColor(col);
if(Petrack::trcVersion > 2)
{
s >> markerID;
tp.setMarkerID(markerID);
}
return s;
}
inline QTextStream &operator<<(QTextStream &s, const TrackPoint &tp)
{
if(Petrack::trcVersion > 2)
{
s << tp.x() << " " << tp.y() << " " << tp.sp().x() << " " << tp.sp().y() << " " << tp.sp().z() << " "
<< tp.qual() << " " << tp.colPoint().x() << " " << tp.colPoint().y() << " " << tp.color() << " "
<< tp.getMarkerID();
}
else if(Petrack::trcVersion == 2)
{
s << tp.x() << " " << tp.y() << " " << tp.sp().x() << " " << tp.sp().y() << " " << tp.sp().z() << " "
<< tp.qual() << " " << tp.colPoint().x() << " " << tp.colPoint().y() << " " << tp.color();
}
else
{
s << tp.x() << " " << tp.y() << " " << tp.qual() << " " << tp.colPoint().x() << " " << tp.colPoint().y() << " "
<< tp.color();
}
return s;
}
inline std::ostream &operator<<(std::ostream &s, const TrackPoint &tp)
{
if(Petrack::trcVersion > 2)
{
s << tp.x() << " " << tp.y() << " " << tp.sp().x() << " " << tp.sp().y() << " " << tp.sp().z() << " "
<< tp.qual() << " " << tp.colPoint().x() << " " << tp.colPoint().y() << " " << tp.color() << " "
<< tp.getMarkerID();
}
else if(Petrack::trcVersion > 1)
{
s << tp.x() << " " << tp.y() << " " << tp.sp().x() << " " << tp.sp().y() << " " << tp.sp().z() << " "
<< tp.qual() << " " << tp.colPoint().x() << " " << tp.colPoint().y() << " " << tp.color();
}
else
{
s << tp.x() << " " << tp.y() << " " << tp.qual() << " " << tp.colPoint().x() << " " << tp.colPoint().y() << " "
<< tp.color();
}
return s;
}
QTextStream & operator>>(QTextStream &s, TrackPoint &tp);
QTextStream & operator<<(QTextStream &s, const TrackPoint &tp);
std::ostream &operator<<(std::ostream &s, const TrackPoint &tp);
//--------------------------------------------------------------------------
......@@ -219,7 +147,7 @@ public:
mHeightCount = 0;
}
void recalcHeight(float altitude);
double getNearestZ(int i, int *extrapolated);
double getNearestZ(int i, int *extrapolated) const;
inline int getMarkerID() const { return mMarkerID; }
inline void setMarkerID(const int markerID) { mMarkerID = markerID; }
......@@ -258,86 +186,11 @@ public:
// mHeightCount wird nicht e3xportiert und auch nicht wieder eingelesen -> nach import auf 0 obwohl auf height ein wert
// steht, daher immer mheight auf -1 testen!!!
// keine Konsistenzueberpruefung
inline QTextStream &operator>>(QTextStream &s, TrackPerson &tp)
{
double d;
QColor col;
int n;
TrackPoint p;
int markerID;
s.skipWhiteSpace();
QString str = s.readLine();
QTextStream trjInfoLine(&str);
trjInfoLine >> n;
tp.setNr(n);
trjInfoLine >> d;
tp.setHeight(d);
trjInfoLine >> n;
tp.setFirstFrame(n);
trjInfoLine >> n;
tp.setLastFrame(n);
trjInfoLine >> n;
tp.setColCount(n);
trjInfoLine >> col;
tp.setColor(col);
if(Petrack::trcVersion > 3)
{
trjInfoLine >> markerID;
tp.setMarkerID(markerID);
}
trjInfoLine >> n; // size of list
if(Petrack::trcVersion > 2) // Reading the comment line
{
// Kommentarzeile lesen
str = s.readLine();
tp.setComment(str.replace(QRegularExpression("<br>"), "\n"));
}
QTextStream &operator>>(QTextStream &s, TrackPerson &tp);
for(int i = 0; i < n; ++i)
{
s >> p;
tp.append(p);
}
return s;
}
QTextStream &operator<<(QTextStream &s, const TrackPerson &tp);
inline QTextStream &operator<<(QTextStream &s, const TrackPerson &tp)
{
s << tp.nr() << " " << tp.height() << " " << tp.firstFrame() << " " << tp.lastFrame() << " " << tp.colCount() << " "
<< tp.color();
if(Petrack::trcVersion > 3)
{
s << " " << tp.getMarkerID();
}
s << " " << tp.size();
s << Qt::endl << tp.serializeComment() << Qt::endl;
for(int i = 0; i < tp.size(); ++i)
{
s << tp.at(i) << Qt::endl;
}
return s;
}
inline std::ostream &operator<<(std::ostream &s, const TrackPerson &tp)
{
s << tp.nr() << " " << tp.height() << " " << tp.firstFrame() << " " << tp.lastFrame() << " " << tp.colCount() << " "
<< tp.color();
if(Petrack::trcVersion > 3)
{
s << " " << tp.getMarkerID();
}
s << " " << tp.size();
s << std::endl << tp.serializeComment() << std::endl;
for(int i = 0; i < tp.size(); ++i)
{
s << tp.at(i) << std::endl;
}
return s;
}
std::ostream &operator<<(std::ostream &s, const TrackPerson &tp);
//----------------------------------------------------------------------------
......@@ -353,7 +206,7 @@ inline std::ostream &operator<<(std::ostream &s, const TrackPerson &tp)
* 6. calculate color over tracking (accumulated over tracking while procedure above) path and set height
* 7. recalc coord with real coord with known height
*/
class Tracker : public QList<TrackPerson>
class Tracker
{
private:
Petrack * mMainWindow;
......@@ -365,9 +218,10 @@ private:
std::vector<int> mPrevFeaturePointsIdx;
std::vector<float> mTrackError;
cv::TermCriteria mTermCriteria;
PersonStorage & mPersonStorage;
public:
Tracker(QWidget *wParent);
Tracker(QWidget *wParent, PersonStorage &storage);
// neben loeschen der liste muessen auch ...
void init(cv::Size size);
......@@ -376,45 +230,6 @@ public:
void resize(cv::Size size);
void splitPerson(int pers, int frame);
bool splitPersonAt(const Vec2F &p, int frame, QSet<int> onlyVisible);
bool delPointOf(int pers, int direction, int frame);
bool delPoint(const Vec2F &p, int direction, int frame, QSet<int> onlyVisible);
void delPointAll(int direction, int frame);
void delPointROI();
void delPointInsideROI();
bool editTrackPersonComment(const Vec2F &p, int frame, const QSet<int> &onlyVisible);
bool setTrackPersonHeight(const Vec2F &p, int frame, QSet<int> onlyVisible);
bool resetTrackPersonHeight(const Vec2F &p, int frame, QSet<int> onlyVisible);
// used for calculation of 3D point for all points in frame
// returns number of found points or -1 if no stereoContext available (also points without disp found are counted)
int calcPosition(int frame);
// true, if new traj is inserted with point p and initial frame frame
// p in pixel coord
// pers wird gesetzt, wenn existierender trackpoint einer person verschoben wird
bool addPoint(
TrackPoint & p,
int frame,
const QSet<int> & onlyVisible,
reco::RecognitionMethod method,
int * pers = nullptr);
// hier sollte direkt die farbe mit uebergeben werden
void addPoints(QList<TrackPoint> &pL, int frame, reco::RecognitionMethod method);
// calculate height of person
// convert all trajectorie coordinates in real coordinate (height needed)
int visible(int frameNum);
int largestFirstFrame();
int largestLastFrame();
int smallestFirstFrame();
int smallestLastFrame();
size_t calcPrevFeaturePoints(
int prevFrame,
cv::Rect &rect,
......@@ -439,32 +254,6 @@ public:
QSet<int> onlyVisible = QSet<int>(),
int errorScaleExponent = 0);
void checkPlausibility(
QList<int> &pers,
QList<int> &frame,
bool testEqual = true,
bool testVelocity = true,
bool testInside = true,
bool testLength = true);
void optimizeColor();
// reset the height of all persons, but not the pos of the trackpoints
void resetHeight();
// reset the pos of the tzrackpoints, but not the heights
void resetPos();
void recalcHeight(float altitude);
void setMarkerHeights(const std::unordered_map<int, float> &heights);
void setMarkerIDs(const std::unordered_map<int, int> &markerIDs);
// gibt groessenverteilung der personen auf stdout aus
// rueckgabewert false wenn keine hoeheninformationen in tracker datensatz vorliegt
bool printHeightDistribution();
void purge(int frame);
private:
bool tryMergeTrajectories(const TrackPoint &v, size_t i, int frame);
......
......@@ -25,17 +25,17 @@
class Petrack;
class Control;
class Tracker;
class PersonStorage;
class TrackerItem : public QGraphicsItem
{
private:
Petrack *mMainWindow;
Control *mControlWidget;
Tracker *mTracker;
Petrack * mMainWindow;
Control * mControlWidget;
PersonStorage &mPersonStorage;
public:
TrackerItem(QWidget *wParent, Tracker *tracker, QGraphicsItem *parent = nullptr);
TrackerItem(QWidget *wParent, PersonStorage &tracker, QGraphicsItem *parent = nullptr);
void contextMenuEvent(QGraphicsSceneContextMenuEvent *event);
QRectF boundingRect() const;
void paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget);
......
......@@ -28,6 +28,8 @@
#include <QList>
class PersonStorage;
// point in x/y in cm
class TrackPointReal : public Vec3F
{
......@@ -115,8 +117,9 @@ inline QTextStream &operator<<(QTextStream &s, const TrackPersonReal &tp)
class TrackerReal : public QList<TrackPersonReal>
{
private:
double mXMin, mXMax, mYMin, mYMax;
Petrack *mMainWindow;
double mXMin, mXMax, mYMin, mYMax;
Petrack * mMainWindow;
PersonStorage &mPersonStorage;
public:
inline double xMin() const { return mXMin; }
......@@ -124,7 +127,7 @@ public:
inline double yMin() const { return mYMin; }
inline double yMax() const { return mYMax; }
TrackerReal(QWidget *wParent);
TrackerReal(QWidget *wParent, PersonStorage &storage);
// calculate height of person
......
......@@ -21,6 +21,8 @@
#ifndef VIEW_H
#define VIEW_H
#include "personStorage.h" // for Direction
#include <QFrame>
#include <QGraphicsView>
#include <QKeyEvent>
......@@ -54,7 +56,7 @@ signals:
void mouseShiftDoubleClick(QPointF pos);
void mouseControlDoubleClick(QPointF pos);
void mouseRightDoubleClick(QPointF pos, int direction);
void mouseMiddleDoubleClick(int direction);
void mouseMiddleDoubleClick(PersonStorage::Direction direction);
void mouseShiftWheel(int delta);
void colorSelected();
void setColorEvent();
......
......@@ -109,10 +109,6 @@ private:
//-----------------------------------------------------------------------------------------
// die kreise liegen mgl nicht genau auf kreuz - noch zu testen
TrackerPlotItem::TrackerPlotItem()
{
mTracker = nullptr;
}
/**
* @brief Draws a circle in the colorplot for every color associated with a trackperson.
......@@ -128,7 +124,7 @@ void TrackerPlotItem::draw(QPainter *p, const QwtScaleMap &mapX, const QwtScaleM
double sy = mapY.p1() / (mapY.s2() - mapY.s1());
double yMax = ((ColorPlot *) plot())->yMax();
double circleSize = ((ColorPlot *) plot())->symbolSize();
int i, z;
int z;
int plotZ = ((ColorPlot *) plot())->zValue();
double diff;
......@@ -143,23 +139,22 @@ void TrackerPlotItem::draw(QPainter *p, const QwtScaleMap &mapX, const QwtScaleM
sx = circleSize / sx;
sy = circleSize / sy;
if(mTracker)
if(mPersonStorage)
{
for(i = 0; i < mTracker->size(); ++i)
const auto &persons = mPersonStorage->getPersons();
for(const auto &person : persons)
{
if((*mTracker)[i]
.color()
.isValid()) // insbesondere von hand eingefuegte trackpoint/persons haben keine farbe
if(person.color().isValid()) // insbesondere von hand eingefuegte trackpoint/persons haben keine farbe
{
QPoint point = ((ColorPlot *) plot())->getPos((*mTracker)[i].color(), &z);
QPoint point = ((ColorPlot *) plot())->getPos(person.color(), &z);
diff = (255. - abs(z - plotZ)) / 255.;
rect.setWidth(diff * sx);
rect.setHeight(diff * sy);
rect.moveLeft(point.x() - diff * sx / 2.);
rect.moveTop(point.y() - diff * sy / 2.);
p->setBrush(QBrush((*mTracker)[i].color()));
if(((ColorPlot *) plot())->isGrey((*mTracker)[i].color()))
p->setBrush(QBrush(person.color()));
if(((ColorPlot *) plot())->isGrey(person.color()))
{
p->setPen(Qt::red);
}
......@@ -180,13 +175,9 @@ void TrackerPlotItem::setPen(const QPen &pen)
mPen = pen;
}
void TrackerPlotItem::setTracker(Tracker *tracker)
{
mTracker = tracker;
}
Tracker *TrackerPlotItem::getTracker()
void TrackerPlotItem::setPersonStorage(const PersonStorage *storage)
{
return mTracker;
mPersonStorage = storage;
}
......@@ -611,9 +602,7 @@ private:
//-----------------------------------------------------------------------------------------
ColorPlot::ColorPlot(QWidget *parent) // default= NULL
:
QwtPlot(parent)
ColorPlot::ColorPlot(QWidget *parent) : QwtPlot(parent)
{
mControlWidget = nullptr;
mGreyDiff = 50;
......@@ -665,14 +654,13 @@ bool ColorPlot::printDistribution() const
{
QMap<double, int> dict;
QMap<double, int>::const_iterator j;
Tracker * tr = mTrackerItem->getTracker();
int i, anz = 0;
int anz = 0;
for(i = 0; i < tr->size(); ++i)
for(auto const &person : mPersonStorage->getPersons())
{
if((*tr)[i].color().isValid()) // insbesondere von hand eingefuegte trackpoint/persons haben keine farbe
if(person.color().isValid()) // insbesondere von hand eingefuegte trackpoint/persons haben keine farbe
{
++dict[map((*tr)[i].color())];
++dict[map(person.color())];
}
}
j = dict.constBegin();
......@@ -831,9 +819,10 @@ void ColorPlot::setControlWidget(Control *control)
mControlWidget = control;
}
void ColorPlot::setTracker(Tracker *tracker)
void ColorPlot::setPersonStorage(const PersonStorage *storage)
{
mTrackerItem->setTracker(tracker);
mPersonStorage = storage;
mTrackerItem->setPersonStorage(storage);
}
void ColorPlot::setScale()
......
......@@ -1247,30 +1247,30 @@ void Control::on_trackShowOnlyNrList_textChanged(const QString & /*arg1*/)
void Control::on_trackGotoNr_clicked()
{
if(mMainWindow->getTracker()->size() >= trackShowOnlyNr->value())
if(static_cast<int>(mMainWindow->getPersonStorage().nbPersons()) >= trackShowOnlyNr->value())
{
int idx = trackShowOnlyNr->value() - 1;
int firstFrame = mMainWindow->getTracker()->at(idx).firstFrame();
int lastFrame = mMainWindow->getTracker()->at(idx).lastFrame();
int firstFrame = mMainWindow->getPersonStorage().at(idx).firstFrame();
int lastFrame = mMainWindow->getPersonStorage().at(idx).lastFrame();
mMainWindow->getPlayer()->skipToFrame((lastFrame + firstFrame) / 2);
}
}
void Control::on_trackGotoStartNr_clicked()
{
if(mMainWindow->getTracker()->size() >= trackShowOnlyNr->value())
if(static_cast<int>(mMainWindow->getPersonStorage().nbPersons()) >= trackShowOnlyNr->value())
{
int idx = trackShowOnlyNr->value() - 1;
mMainWindow->getPlayer()->skipToFrame(mMainWindow->getTracker()->at(idx).firstFrame());
mMainWindow->getPlayer()->skipToFrame(mMainWindow->getPersonStorage().at(idx).firstFrame());
}
}
void Control::on_trackGotoEndNr_clicked()
{
if(mMainWindow->getTracker()->size() >= trackShowOnlyNr->value())
if(static_cast<int>(mMainWindow->getPersonStorage().nbPersons()) >= trackShowOnlyNr->value())
{
int idx = trackShowOnlyNr->value() - 1;
mMainWindow->getPlayer()->skipToFrame(mMainWindow->getTracker()->at(idx).lastFrame());
mMainWindow->getPlayer()->skipToFrame(mMainWindow->getPersonStorage().at(idx).lastFrame());
}
}
......@@ -1285,7 +1285,7 @@ void Control::on_trackShowOnlyListButton_clicked()
QGridLayout * layout = (QGridLayout *) nrListBox.layout();
QVector<QCheckBox *> checkBox;
for(int i = 0; i < mMainWindow->getTracker()->size(); i++)
for(int i = 0; i < static_cast<int>(mMainWindow->getPersonStorage().nbPersons()); i++)
{
/// ToDo: parse from lineEdit
checkBox.push_back(new QCheckBox(QString::number(i + 1)));
......@@ -1305,7 +1305,7 @@ void Control::on_trackShowOnlyListButton_clicked()
{
QStringList list;
int first = -1, last = -1;
for(int i = 0; i < mMainWindow->getTracker()->size(); i++)
for(int i = 0; i < static_cast<int>(mMainWindow->getPersonStorage().nbPersons()); i++)
{
if(checkBox.at(i)->isChecked())
{
......@@ -1378,7 +1378,7 @@ void Control::on_recoShowColor_stateChanged(int i)
void Control::on_recoOptimizeColor_clicked()
{
mMainWindow->getTracker()->optimizeColor();
mMainWindow->getPersonStorage().optimizeColor();
colorPlot->replot();
mScene->update(); // damit mgl angezeige farbpunkte geaendert/weggenommen werden
}
......@@ -1675,17 +1675,17 @@ void Control::on_mapDistribution_clicked()
{
if(!colorPlot->printDistribution())
{
mMainWindow->getTracker()->printHeightDistribution();
mMainWindow->getPersonStorage().printHeightDistribution();
}
}
void Control::on_mapResetHeight_clicked()
{
mMainWindow->getTracker()->resetHeight();
mMainWindow->getPersonStorage().resetHeight();
mScene->update();
}
void Control::on_mapResetPos_clicked()
{
mMainWindow->getTracker()->resetPos();
mMainWindow->getPersonStorage().resetPos();
mScene->update();
}
void Control::on_mapDefaultHeight_valueChanged(double d)
......@@ -1706,8 +1706,8 @@ void Control::on_mapReadHeights_clicked()
if(std::holds_alternative<std::unordered_map<int, float>>(heights)) // heights contains the height map
{
mMainWindow->getTracker()->resetHeight();
mMainWindow->getTracker()->setMarkerHeights(std::get<std::unordered_map<int, float>>(heights));
mMainWindow->getPersonStorage().resetHeight();
mMainWindow->getPersonStorage().setMarkerHeights(std::get<std::unordered_map<int, float>>(heights));
mMainWindow->setHeightFileName(heightFile);
}
else // heights contains an error string
......@@ -1715,7 +1715,7 @@ void Control::on_mapReadHeights_clicked()
PCritical(mMainWindow, Petrack::tr("PeTrack"), Petrack::tr(std::get<std::string>(heights).c_str()));
}
mMainWindow->getTracker()->printHeightDistribution();
mMainWindow->getPersonStorage().printHeightDistribution();
mScene->update();
}
......@@ -1731,7 +1731,7 @@ void Control::on_mapReadMarkerID_clicked()
if(std::holds_alternative<std::unordered_map<int, int>>(markerIDs)) // markerIDs contains the marker information
{
mMainWindow->getTracker()->setMarkerIDs(std::get<std::unordered_map<int, int>>(markerIDs));
mMainWindow->getPersonStorage().setMarkerIDs(std::get<std::unordered_map<int, int>>(markerIDs));
mMainWindow->setMarkerIDFileName(markerFile);
}
else // heights contains an error string
......@@ -1740,7 +1740,7 @@ void Control::on_mapReadMarkerID_clicked()
mMainWindow, Petrack::tr("PeTrack"), Petrack::tr(std::get<std::string>(markerIDs).c_str()));
}
mMainWindow->getTracker()->printHeightDistribution();
mMainWindow->getPersonStorage().printHeightDistribution();
mScene->update();
}
......
......@@ -29,7 +29,7 @@
#define MAX_AV_ERROR 20
ExtrCalibration::ExtrCalibration()
ExtrCalibration::ExtrCalibration(PersonStorage &storage) : mPersonStorage(storage)
{
mMainWindow = nullptr;
mControlWidget = nullptr;
......@@ -316,7 +316,7 @@ bool ExtrCalibration::loadExtrCalibFile()
bool ExtrCalibration::fetch2DPoints()
{
bool all_ok = true;
if(!mMainWindow->getTracker() || mMainWindow->getTracker()->size() < 4)
if(!mMainWindow->getTracker() || mPersonStorage.nbPersons() < 4)
{
PCritical(
mMainWindow,
......@@ -326,7 +326,7 @@ bool ExtrCalibration::fetch2DPoints()
}
else
{
size_t sz_2d = mMainWindow->getTracker()->size();
size_t sz_2d = mPersonStorage.nbPersons();
if(points3D.size() > 0 && sz_2d != points3D.size())
{
......@@ -346,14 +346,13 @@ bool ExtrCalibration::fetch2DPoints()
// debout << "[" << i << "]: (" << mMainWindow->getTracker()->at(i).at(0).x() << ", " <<
// mMainWindow->getTracker()->at(i).at(0).y() << ")" << endl;
// Info: Tracker->TrackPerson->TrackPoint->Vec2F
points2D.push_back(cv::Point2f(
mMainWindow->getTracker()->at(i).at(0).x(), mMainWindow->getTracker()->at(i).at(0).y()));
points2D.push_back(cv::Point2f(mPersonStorage.at(i).at(0).x(), mPersonStorage.at(i).at(0).y()));
}
}
}
if(all_ok)
{
mMainWindow->getTracker()->clear();
mPersonStorage.clear();
calibExtrParams();
}
return all_ok;
......
......@@ -210,7 +210,7 @@ int main(int argc, char *argv[])
auto markerIDs = IO::readMarkerIDFile(autoReadMarkerFile);
if(std::holds_alternative<std::unordered_map<int, int>>(markerIDs)) // heights contains the height map
{
petrack.getTracker()->setMarkerIDs(std::get<std::unordered_map<int, int>>(markerIDs));
petrack.getPersonStorage().setMarkerIDs(std::get<std::unordered_map<int, int>>(markerIDs));
petrack.setMarkerIDFileName(autoReadHeightFile);
}
else // markerIDs contains an error string
......@@ -225,8 +225,8 @@ int main(int argc, char *argv[])
auto markerHeights = IO::readHeightFile(autoReadHeightFile);
if(std::holds_alternative<std::unordered_map<int, float>>(markerHeights)) // heights contains the height map
{
petrack.getTracker()->resetHeight();
petrack.getTracker()->setMarkerHeights(std::get<std::unordered_map<int, float>>(markerHeights));
petrack.getPersonStorage().resetHeight();
petrack.getPersonStorage().setMarkerHeights(std::get<std::unordered_map<int, float>>(markerHeights));
petrack.setHeightFileName(autoReadHeightFile);
}
else // markerHeights contains an error string
......@@ -261,7 +261,7 @@ int main(int argc, char *argv[])
auto markerIDs = IO::readMarkerIDFile(autoReadMarkerFile);
if(std::holds_alternative<std::unordered_map<int, int>>(markerIDs)) // heights contains the height map
{
petrack.getTracker()->setMarkerIDs(std::get<std::unordered_map<int, int>>(markerIDs));
petrack.getPersonStorage().setMarkerIDs(std::get<std::unordered_map<int, int>>(markerIDs));
petrack.setMarkerIDFileName(autoReadHeightFile);
}
else // heights contains an error string
......@@ -276,8 +276,8 @@ int main(int argc, char *argv[])
auto markerHeights = IO::readHeightFile(autoReadHeightFile);
if(std::holds_alternative<std::unordered_map<int, float>>(markerHeights)) // heights contains the height map
{
petrack.getTracker()->resetHeight();
petrack.getTracker()->setMarkerHeights(std::get<std::unordered_map<int, float>>(markerHeights));
petrack.getPersonStorage().resetHeight();
petrack.getPersonStorage().setMarkerHeights(std::get<std::unordered_map<int, float>>(markerHeights));
petrack.setHeightFileName(autoReadHeightFile);
}
else // heights contains an error string
......
......@@ -25,6 +25,7 @@
#include "ui_openMoCapDialog.h"
#include <QFileDialog>
#include <QMessageBox>
OpenMoCapDialog::OpenMoCapDialog(QWidget *parent, MoCapController &controller) :
QDialog(parent), mUi(new Ui::OpenMoCapDialog), mController(controller), mParent(parent)
......
This diff is collapsed.
This diff is collapsed.
......@@ -161,7 +161,7 @@ void setColorParameter(const QColor &fromColor, const QColor &toColor, bool inve
* @param controlWidget
* @return
*/
Vec2F autoCorrectColorMarker(Vec2F &boxImageCentre, Control *controlWidget)
Vec2F autoCorrectColorMarker(const Vec2F &boxImageCentre, Control *controlWidget)
{
Petrack * mainWindow = controlWidget->getMainWindow();
cv::Point2f tp = mainWindow->getExtrCalibration()->getImagePoint(cv::Point3f(
......
This diff is collapsed.