ptuwindow.h
Go to the documentation of this file.
00001 
00018 #ifndef PTUWINDOW_H
00019 #define PTUWINDOW_H
00020 #include "CameraUtils/ptu_manager.h"
00021 #include "CameraUtils/marker_manager.h"
00022 #include "CameraUtils/camerathread.h"
00023 #include <QDialog>
00024 #include <QBitmap>
00025 #include <QLabel>
00026 
00027 #include <QPushButton>
00028 #include "calibration_object.h"
00029 #include "VisualisationUtils/camerawidget.h"
00030 #include "VisualisationUtils/markerpublisher.h"
00031 #include <Transformation/transformation_data.h>
00032 #include <Transformation/transformation_publisher.h>
00033 #include <Transformation/transformationfile_manager_data.h>
00034 #ifndef Q_MOC_RUN
00035 #include <sensor_msgs/Image.h>
00036 #include <Eigen/Dense>
00037 #include <boost/shared_ptr.hpp>
00038 #include <tf/tf.h>
00039 #include <tf_conversions/tf_eigen.h>
00040 #include <tf/transform_datatypes.h>
00041 #include <tf_conversions/tf_eigen.h>
00042 #include <tf/transform_listener.h>
00043 
00044 #endif
00045 
00046 
00047 class PTUWindow : public QDialog
00048 {
00049     Q_OBJECT
00050 public:
00051     explicit PTUWindow(QWidget *parent = 0);
00052     PTUWindow( boost::shared_ptr<MarkerPublisher> markerManager, boost::shared_ptr<Calibration_Object> calibrationObject, boost::shared_ptr<Transformation_Publisher> transformationPublisher, const Eigen::Matrix4d calObjTransformation, QWidget *parent =0);
00053     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00054 private:
00055     void init(boost::shared_ptr<MarkerPublisher> markerManager, boost::shared_ptr<Calibration_Object> calibrationObject, boost::shared_ptr<Transformation_Publisher> transformationPublisher, const Eigen::Matrix4d calObjTransformation);
00056     void startCapture();
00057     void stopMarkerCapturing();
00058     void setUI_Elements();
00059     void calculateAllAverageDataFrames();
00060     Eigen::Matrix4d calculateAverageDataFrame(std::vector<Eigen::Matrix4d , Eigen::aligned_allocator<Eigen::Matrix4d > > frames);
00061     PTU_Manager * ptuManager;
00062     Marker_Manager * markerManager;
00063 
00064     QPushButton *btnStartStopPTUSearch;
00065     QPushButton *btnSkipFramePTUSearch;
00066     QPushButton *btnExportCameraPoses;
00067     QPushButton *btnExportRelativeMarkerPoses;
00068     QPushButton *btnExportCameraOffset;
00069 
00070     QLabel *lblCameraFrameCount;
00071     QLabel *lblRelativeMarkerFrameCount;
00072 
00073     CameraWidget * cameraLeft;
00074     CameraWidget * cameraRight;
00075 
00076     bool slotEnabled_PTU;
00077     bool slotEnabled_Marker;
00078     bool stopSignal;
00079 
00080     //Defines if raw marker position or averaged postions over all markers per frame are used
00081     bool useAveragedMarkerData;
00082 
00083     //Used to publish the current results to ros
00084     boost::shared_ptr<MarkerPublisher> markerPublisher;
00085 
00086     double marker_min_distance;
00087     double marker_max_distance;
00088     double tilt_min_angle;
00089     double tilt_max_angle;
00090     double pan_min_angle;
00091     double pan_max_angle;
00092 
00093     tf::TransformListener * mTFlistener;
00094 
00095     //Publishes transformation frames to tf
00096     boost::shared_ptr<Transformation_Publisher> transformationPublisher;
00097 
00098     //Contains all the parameters of the calibration object
00099     boost::shared_ptr<Calibration_Object> calibrationObject;
00100 
00101     Eigen::Matrix4d transformation_LaserScanner;
00102     std::vector<colouredCameraFrame, Eigen::aligned_allocator<colouredCameraFrame> > colouredCameraFrames;
00103     std::vector<Transformation_Data> transformationData;
00104 
00105     std::vector<Transformation_Data> tempTransformationData;
00106 
00107     std::vector<Eigen::Matrix4d , Eigen::aligned_allocator<Eigen::Matrix4d > > relativeMarkerPoses;
00108     std::vector<Eigen::Matrix4d , Eigen::aligned_allocator<Eigen::Matrix4d > > markerRightPoses;
00109     std::vector<Eigen::Matrix4d , Eigen::aligned_allocator<Eigen::Matrix4d > > markerLeftPoses;
00110     //Used to save collected data for left and right frame in order to calculte the average frames afterwards
00111     std::vector<Eigen::Matrix4d , Eigen::aligned_allocator<Eigen::Matrix4d > > tempMarkerRightPoses;
00112     std::vector<Eigen::Matrix4d , Eigen::aligned_allocator<Eigen::Matrix4d > > tempMarkerLeftPoses;
00113     //Used for evaluation
00114     PanTiltOffsetTupleList cameraOffsetParameters;
00115 
00116     void handleNewTransformationData(Transformation_Data &data);
00117     void resizeEvent(QResizeEvent * event);
00118     bool markerPoseWithinBounds(const Eigen::Matrix4d& transform);
00119 signals:
00120     void newTransform_Camera(const Eigen::Matrix4d& transform, Markertype markertype);
00121 public slots:
00122     void btnStartStopPTUSearch_clicked();
00123     void btnExportCameraPoses_clicked();
00124     void btnExportRelativeMarkerPoses_clicked();
00125     void btnSkipFramePTUSearch_clicked();
00126     void btnExportCameraOffset_clicked();
00127     void ptu_moved(double pan, double tilt);
00128     void markerFound(std::string markerNumber, const Eigen::Matrix4d &transformation);
00129 };
00130 
00131 #endif // PTUWINDOW_H


asr_mild_calibration_tool
Author(s): Aumann Florian, Heller Florian, Meißner Pascal
autogenerated on Thu Jun 6 2019 21:22:44