Skip to content

Commit

Permalink
Merge branch 'gray-out-calib-4' into 'master'
Browse files Browse the repository at this point in the history
Gray out calib 4

See merge request ped-dyn-emp/petrack!284
  • Loading branch information
Kilidsch committed Jun 21, 2023
2 parents 802f6c0 + ff18f57 commit 23edcee
Show file tree
Hide file tree
Showing 41 changed files with 3,334 additions and 2,693 deletions.
5 changes: 5 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -393,9 +393,12 @@ target_sources(petrack_core PRIVATE
include/logwindow.h
include/extrinsicBox.h
include/extrinsicParameters.h
include/coordinateSystemBox.h
include/worldImageCorrespondence.h
include/autosaveSettings.h
include/editMoCapDialog.h
include/moCapEditingWidget.h
include/coordinateStructs.h
)

target_sources(petrack_core PRIVATE
Expand Down Expand Up @@ -465,8 +468,10 @@ target_sources(petrack_core PRIVATE
src/logwindow.cpp
src/extrinsicBox.cpp
src/autosaveSettings.cpp
src/coordinateSystemBox.cpp
src/editMoCapDialog.cpp
src/moCapEditingWidget.cpp
ui/coordinateSystemBox.ui
ui/moCapEditingWidget.ui
ui/editMoCapDialog.ui
ui/about.ui
Expand Down
151 changes: 56 additions & 95 deletions include/control.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,11 +19,8 @@
#ifndef CONTROL_H
#define CONTROL_H

#include "analysePlot.h"
#include "colorPlot.h"
#include "extrinsicParameters.h"
#include "coordinateStructs.h"
#include "intrinsicCameraParams.h"
#include "petrack.h"
#include "recognition.h"

#include <Qt>
Expand All @@ -33,7 +30,16 @@ class QGraphicsScene;
class QDomElement;
class IntrinsicBox;
class ExtrinsicBox;
struct ExtrinsicParameters;
class FilterBeforeBox;
class Petrack;
class RoiItem;
class RectPlotItem;
class CoordinateSystemBox;
class ColorPlot;
class AnalysePlot;
class MissingFrames;
class WorldImageCorrespondence;
namespace Ui
{
class Control;
Expand All @@ -45,22 +51,28 @@ class Control : public QWidget

public:
Control(
QWidget &parent,
QGraphicsScene &scene,
reco::Recognizer &recognizer,
RoiItem &trackRoiItem,
RoiItem &recoRoiItem,
MissingFrames &missingFrames,
FilterBeforeBox *filterBefore);
QWidget &parent,
QGraphicsScene &scene,
reco::Recognizer &recognizer,
RoiItem &trackRoiItem,
RoiItem &recoRoiItem,
MissingFrames &missingFrames,
FilterBeforeBox *filterBefore,
IntrinsicBox *intrinsicBox,
ExtrinsicBox *extrinsicBox,
CoordinateSystemBox *coordSysBox);
Control(
QWidget &parent,
QGraphicsScene &scene,
reco::Recognizer &recognizer,
RoiItem &trackRoiItem,
RoiItem &recoRoiItem,
Ui::Control *ui,
MissingFrames &missingFrames,
FilterBeforeBox *filterBefore);
QWidget &parent,
QGraphicsScene &scene,
reco::Recognizer &recognizer,
RoiItem &trackRoiItem,
RoiItem &recoRoiItem,
Ui::Control *ui,
MissingFrames &missingFrames,
FilterBeforeBox *filterBefore,
IntrinsicBox *intrinsicBox,
ExtrinsicBox *extrinsicBox,
CoordinateSystemBox *coordSysBox);

void setScene(QGraphicsScene *sc);

Expand Down Expand Up @@ -152,53 +164,20 @@ class Control : public QWidget

double getCalibReprError() const;
void setCalibReprError(double d);
void imageSizeChanged(int width, int height, int borderDiff);

const ExtrinsicParameters &getExtrinsicParameters() const;

int getCalibCoordDimension();
bool getCalibExtrCalibPointsShow();
bool getCalibExtrVanishPointsShow();
bool getCalibCoordShow();
void setCalibCoordShow(bool b);
bool getCalibCoordFix();
void setCalibCoordFix(bool b);
bool getIs3DView();
void setIs3DView(bool b);
int getCalibCoordRotate();
void setCalibCoordRotate(int i);
int getCalibCoordTransX();
void setCalibCoordTransX(int i);
int getCalibCoordTransXMax();
void setCalibCoordTransXMax(int i);
int getCalibCoordTransXMin();
void setCalibCoordTransXMin(int i);
int getCalibCoordTransY();
void setCalibCoordTransY(int i);
int getCalibCoordTransYMax();
void setCalibCoordTransYMax(int i);
int getCalibCoordTransYMin();
void setCalibCoordTransYMin(int i);
int getCalibCoordScale();
void setCalibCoordScale(int i);
double getCalibCoordUnit();
void setCalibCoordUnit(double d);
bool isCoordUseIntrinsicChecked() const;

int getCalibCoord3DTransX();
void setCalibCoord3DTransX(int i);
int getCalibCoord3DTransY();
void setCalibCoord3DTransY(int i);
int getCalibCoord3DTransZ();
void setCalibCoord3DTransZ(int i);
int getCalibCoord3DAxeLen();
void setCalibCoord3DAxeLen(int i);
bool getCalibCoord3DSwapX();
void setCalibCoord3DSwapX(bool b);
bool getCalibCoord3DSwapY();
void setCalibCoord3DSwapY(bool b);
bool getCalibCoord3DSwapZ();
void setCalibCoord3DSwapZ(bool b);
const WorldImageCorrespondence &getWorldImageCorrespondence() const;
void setCalibCoord2DTransMinMax(Vec2F min, Vec2F max);
Vec2F getCalibCoord2DTrans();

Vec3F getCalibCoord3DTrans() const;
SwapAxis getCalibCoord3DSwap() const;

int getCalibCoordDimension();
bool getCalibCoordShow();
int getCalibCoordScale();


int getCalibGridDimension();
bool getCalibGridShow();
Expand Down Expand Up @@ -233,7 +212,7 @@ class Control : public QWidget

void setXml(QDomElement &elem);
void getXml(const QDomElement &elem);
bool isLoading() const { return mMainWindow->isLoading(); }
bool isLoading() const;
ColorPlot *getColorPlot() const;
void replotColorplot();

Expand Down Expand Up @@ -542,18 +521,6 @@ private slots:

void on_intrinsicParamsChanged(IntrinsicCameraParams params);

void on_coordShow_stateChanged(int i);
void on_coordFix_stateChanged(int i);
void on_coordRotate_valueChanged(int i);
void on_coordTransX_valueChanged(int i);
void on_coordTransY_valueChanged(int i);
void on_coordScale_valueChanged(int i);
void on_coordAltitude_valueChanged(double d);
void on_coordUnit_valueChanged(double d);
void on_coordUseIntrinsic_stateChanged(int i);

void setMeasuredAltitude();

void on_gridShow_stateChanged(int i);
void on_gridFix_stateChanged(int i);
void on_gridRotate_valueChanged(int i);
Expand All @@ -562,23 +529,11 @@ private slots:
void on_gridScale_valueChanged(int i);

void on_gridTab_currentChanged(int index);
void on_coordTab_currentChanged(int index);

void on_extCalibPointsShow_stateChanged(int arg1);
void on_extVanishPointsShow_stateChanged(int arg1);

void on_grid3DTransX_valueChanged(int value);
void on_grid3DTransY_valueChanged(int value);
void on_grid3DTransZ_valueChanged(int value);
void on_grid3DResolution_valueChanged(int value);
void on_coord3DTransX_valueChanged(int value);
void on_coord3DTransY_valueChanged(int value);
void on_coord3DTransZ_valueChanged(int value);
void on_coord3DAxeLen_valueChanged(int value);

void on_coord3DSwapX_stateChanged(int arg1);
void on_coord3DSwapY_stateChanged(int arg1);
void on_coord3DSwapZ_stateChanged(int arg1);

void on_trackPathColorButton_clicked();
void on_trackGroundPathColorButton_clicked();
Expand All @@ -604,17 +559,23 @@ private slots:
void toggleRecoROIButtons();
void toggleTrackROIButtons();

public slots:
void imageSizeChanged(int width, int height, int borderDiff);


signals:
void userChangedRecoMethod(reco::RecognitionMethod method);


private:
Petrack *mMainWindow;
Ui::Control *mUi;
IntrinsicBox *mIntr;
FilterBeforeBox *mFilterBefore;
ExtrinsicBox *mExtr;
QGraphicsScene *mScene;
bool mColorChanging;
Petrack *mMainWindow;
Ui::Control *mUi;
IntrinsicBox *mIntr;
FilterBeforeBox *mFilterBefore;
ExtrinsicBox *mExtr;
CoordinateSystemBox *mCoordSys;
QGraphicsScene *mScene;
bool mColorChanging;
bool mIndexChanging; // shows, if the index of the color model is really changing; nor while constructor (initialer
// durchlauf) and may be while loading xml file
bool mLoading; // shows, if new project is just loading
Expand Down
39 changes: 22 additions & 17 deletions include/coordItem.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,37 +26,42 @@
class Petrack;
class Control;
class ExtrCalibration;
class CoordinateSystemBox;
struct CoordPose2D;
struct CoordPose3D;

class CoordItem : public QGraphicsItem
class CoordItem : public QGraphicsObject
{
private:
Petrack *mMainWindow;
ExtrCalibration *extCalib;
Control *mControlWidget;
cv::Point2f ursprung, x, y, z;
cv::Point2f calibPointsMin, calibPointsMax;
cv::Point3f x3D, y3D, z3D;
float mouse_x, mouse_y;
int coordTrans_x, coordTrans_y;
int coordDimension;
Petrack *mMainWindow;
ExtrCalibration *extCalib;
Control *mControlWidget;
CoordinateSystemBox *mCoordSys;
QRectF mBoundingRect;
cv::Point3f x3D, y3D, z3D;
float mouse_x, mouse_y;
int coordTrans_x, coordTrans_y;
int coordDimension;

public:
inline void setCoordDimension(int dim) { this->coordDimension = dim; }
inline int getCoordDimension() const { return this->coordDimension; }

CoordItem(QWidget *wParent, QGraphicsItem *parent = nullptr);
CoordItem(QWidget *wParent, QGraphicsItem *parent, CoordinateSystemBox *coordSys);

void mouseMoveEvent(QGraphicsSceneMouseEvent *event);
void mousePressEvent(QGraphicsSceneMouseEvent *event);
void mouseMoveEvent(QGraphicsSceneMouseEvent *event) override;
void mousePressEvent(QGraphicsSceneMouseEvent *event) override;

// Update the transformation matrix
void updateData();

// defines the minimal rect which contains the coordinate system
QRectF boundingRect() const;
QRectF boundingRect() const override;

// paint method to draw the perspectiv coordinate-system
void paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget);
void paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget) override;

private slots:
// Update the transformation matrix
void updateData();
};

#endif
50 changes: 50 additions & 0 deletions include/coordinateStructs.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
/*
* PeTrack - Software for tracking pedestrians movement in videos
* Copyright (C) 2023 Forschungszentrum Jülich GmbH, IAS-7
*
* 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 COORDINATESTRUCTS_H
#define COORDINATESTRUCTS_H

#include "vector.h"

struct CoordPose2D
{
Vec2F position;
double angle;
double scale;
double unit;
};

struct SwapAxis
{
bool x;
bool y;
bool z;
};

inline bool operator==(const SwapAxis &lhs, const SwapAxis &rhs)
{
return (lhs.x == rhs.x) && (lhs.y == rhs.y) && (lhs.z == rhs.z);
}

struct CoordPose3D
{
Vec3F position;
SwapAxis swap;
};

#endif // COORDINATESTRUCTS_H
Loading

0 comments on commit 23edcee

Please sign in to comment.