ptuwindow.h
Go to the documentation of this file.
1 
18 #ifndef PTUWINDOW_H
19 #define PTUWINDOW_H
23 #include <QDialog>
24 #include <QBitmap>
25 #include <QLabel>
26 
27 #include <QPushButton>
28 #include "calibration_object.h"
34 #ifndef Q_MOC_RUN
35 #include <sensor_msgs/Image.h>
36 #include <Eigen/Dense>
37 #include <boost/shared_ptr.hpp>
38 #include <tf/tf.h>
39 #include <tf_conversions/tf_eigen.h>
40 #include <tf/transform_datatypes.h>
41 #include <tf_conversions/tf_eigen.h>
42 #include <tf/transform_listener.h>
43 
44 #endif
45 
46 
47 class PTUWindow : public QDialog
48 {
49  Q_OBJECT
50 public:
51  explicit PTUWindow(QWidget *parent = 0);
53  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
54 private:
55  void init(boost::shared_ptr<MarkerPublisher> markerManager, boost::shared_ptr<Calibration_Object> calibrationObject, boost::shared_ptr<Transformation_Publisher> transformationPublisher, const Eigen::Matrix4d calObjTransformation);
56  void startCapture();
57  void stopMarkerCapturing();
58  void setUI_Elements();
60  Eigen::Matrix4d calculateAverageDataFrame(std::vector<Eigen::Matrix4d , Eigen::aligned_allocator<Eigen::Matrix4d > > frames);
63 
64  QPushButton *btnStartStopPTUSearch;
65  QPushButton *btnSkipFramePTUSearch;
66  QPushButton *btnExportCameraPoses;
68  QPushButton *btnExportCameraOffset;
69 
72 
75 
78  bool stopSignal;
79 
80  //Defines if raw marker position or averaged postions over all markers per frame are used
82 
83  //Used to publish the current results to ros
85 
90  double pan_min_angle;
91  double pan_max_angle;
92 
93  tf::TransformListener * mTFlistener;
94 
95  //Publishes transformation frames to tf
97 
98  //Contains all the parameters of the calibration object
100 
102  std::vector<colouredCameraFrame, Eigen::aligned_allocator<colouredCameraFrame> > colouredCameraFrames;
103  std::vector<Transformation_Data> transformationData;
104 
105  std::vector<Transformation_Data> tempTransformationData;
106 
107  std::vector<Eigen::Matrix4d , Eigen::aligned_allocator<Eigen::Matrix4d > > relativeMarkerPoses;
108  std::vector<Eigen::Matrix4d , Eigen::aligned_allocator<Eigen::Matrix4d > > markerRightPoses;
109  std::vector<Eigen::Matrix4d , Eigen::aligned_allocator<Eigen::Matrix4d > > markerLeftPoses;
110  //Used to save collected data for left and right frame in order to calculte the average frames afterwards
111  std::vector<Eigen::Matrix4d , Eigen::aligned_allocator<Eigen::Matrix4d > > tempMarkerRightPoses;
112  std::vector<Eigen::Matrix4d , Eigen::aligned_allocator<Eigen::Matrix4d > > tempMarkerLeftPoses;
113  //Used for evaluation
115 
117  void resizeEvent(QResizeEvent * event);
118  bool markerPoseWithinBounds(const Eigen::Matrix4d& transform);
119 signals:
120  void newTransform_Camera(const Eigen::Matrix4d& transform, Markertype markertype);
121 public slots:
127  void ptu_moved(double pan, double tilt);
128  void markerFound(std::string markerNumber, const Eigen::Matrix4d &transformation);
129 };
130 
131 #endif // PTUWINDOW_H
std::vector< Eigen::Matrix4d, Eigen::aligned_allocator< Eigen::Matrix4d > > markerRightPoses
Definition: ptuwindow.h:108
std::vector< Eigen::Matrix4d, Eigen::aligned_allocator< Eigen::Matrix4d > > tempMarkerLeftPoses
Definition: ptuwindow.h:112
void setUI_Elements()
Definition: ptuwindow.cpp:142
double pan_min_angle
Definition: ptuwindow.h:90
CameraWidget * cameraRight
Definition: ptuwindow.h:74
std::vector< Eigen::Matrix4d, Eigen::aligned_allocator< Eigen::Matrix4d > > markerLeftPoses
Definition: ptuwindow.h:109
QPushButton * btnExportCameraOffset
Definition: ptuwindow.h:68
std::vector< Transformation_Data > tempTransformationData
Definition: ptuwindow.h:105
double marker_max_distance
Definition: ptuwindow.h:87
bool stopSignal
Definition: ptuwindow.h:78
double marker_min_distance
Definition: ptuwindow.h:86
bool markerPoseWithinBounds(const Eigen::Matrix4d &transform)
Definition: ptuwindow.cpp:528
void resizeEvent(QResizeEvent *event)
Definition: ptuwindow.cpp:171
bool slotEnabled_Marker
Definition: ptuwindow.h:77
void btnSkipFramePTUSearch_clicked()
Definition: ptuwindow.cpp:187
std::vector< PanTiltOffsetTuple, Eigen::aligned_allocator< Eigen::Vector4f > > PanTiltOffsetTupleList
boost::shared_ptr< MarkerPublisher > markerPublisher
Definition: ptuwindow.h:84
std::vector< colouredCameraFrame, Eigen::aligned_allocator< colouredCameraFrame > > colouredCameraFrames
Definition: ptuwindow.h:102
boost::shared_ptr< Transformation_Publisher > transformationPublisher
Definition: ptuwindow.h:96
void stopMarkerCapturing()
Definition: ptuwindow.cpp:432
tf::TransformListener * mTFlistener
Definition: ptuwindow.h:93
void btnExportRelativeMarkerPoses_clicked()
Definition: ptuwindow.cpp:242
QLabel * lblRelativeMarkerFrameCount
Definition: ptuwindow.h:71
Marker_Manager * markerManager
Definition: ptuwindow.h:62
PTUWindow(QWidget *parent=0)
Definition: ptuwindow.cpp:24
QPushButton * btnSkipFramePTUSearch
Definition: ptuwindow.h:65
void markerFound(std::string markerNumber, const Eigen::Matrix4d &transformation)
Definition: ptuwindow.cpp:307
std::vector< Eigen::Matrix4d, Eigen::aligned_allocator< Eigen::Matrix4d > > relativeMarkerPoses
Definition: ptuwindow.h:107
double pan_max_angle
Definition: ptuwindow.h:91
PanTiltOffsetTupleList cameraOffsetParameters
Definition: ptuwindow.h:114
void newTransform_Camera(const Eigen::Matrix4d &transform, Markertype markertype)
QPushButton * btnExportCameraPoses
Definition: ptuwindow.h:66
void btnExportCameraPoses_clicked()
Definition: ptuwindow.cpp:228
void handleNewTransformationData(Transformation_Data &data)
Definition: ptuwindow.cpp:290
std::vector< Transformation_Data > transformationData
Definition: ptuwindow.h:103
CameraWidget * cameraLeft
Definition: ptuwindow.h:73
Eigen::Matrix4d calculateAverageDataFrame(std::vector< Eigen::Matrix4d, Eigen::aligned_allocator< Eigen::Matrix4d > > frames)
Definition: ptuwindow.cpp:503
std::vector< Eigen::Matrix4d, Eigen::aligned_allocator< Eigen::Matrix4d > > tempMarkerRightPoses
Definition: ptuwindow.h:111
void btnStartStopPTUSearch_clicked()
Definition: ptuwindow.cpp:195
void ptu_moved(double pan, double tilt)
Definition: ptuwindow.cpp:551
QPushButton * btnExportRelativeMarkerPoses
Definition: ptuwindow.h:67
QPushButton * btnStartStopPTUSearch
Definition: ptuwindow.h:64
QLabel * lblCameraFrameCount
Definition: ptuwindow.h:70
void init(boost::shared_ptr< MarkerPublisher > markerManager, boost::shared_ptr< Calibration_Object > calibrationObject, boost::shared_ptr< Transformation_Publisher > transformationPublisher, const Eigen::Matrix4d calObjTransformation)
Definition: ptuwindow.cpp:39
boost::shared_ptr< Calibration_Object > calibrationObject
Definition: ptuwindow.h:99
void calculateAllAverageDataFrames()
Definition: ptuwindow.cpp:471
bool useAveragedMarkerData
Definition: ptuwindow.h:81
void startCapture()
Definition: ptuwindow.cpp:256
void btnExportCameraOffset_clicked()
Definition: ptuwindow.cpp:213
Eigen::Matrix4d transformation_LaserScanner
Definition: ptuwindow.h:101
PTU_Manager * ptuManager
Definition: ptuwindow.h:61
bool slotEnabled_PTU
Definition: ptuwindow.h:76
double tilt_min_angle
Definition: ptuwindow.h:88
double tilt_max_angle
Definition: ptuwindow.h:89


asr_mild_calibration_tool
Author(s): Aumann Florian, Heller Florian, Meißner Pascal
autogenerated on Mon Dec 2 2019 03:11:43