Public Slots | Signals | Public Member Functions | Private Member Functions | Private Attributes
PTUWindow Class Reference

#include <ptuwindow.h>

List of all members.

Public Slots

void btnExportCameraOffset_clicked ()
void btnExportCameraPoses_clicked ()
void btnExportRelativeMarkerPoses_clicked ()
void btnSkipFramePTUSearch_clicked ()
void btnStartStopPTUSearch_clicked ()
void markerFound (std::string markerNumber, const Eigen::Matrix4d &transformation)
void ptu_moved (double pan, double tilt)

Signals

void newTransform_Camera (const Eigen::Matrix4d &transform, Markertype markertype)

Public Member Functions

 PTUWindow (QWidget *parent=0)
 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)

Private Member Functions

void calculateAllAverageDataFrames ()
Eigen::Matrix4d calculateAverageDataFrame (std::vector< Eigen::Matrix4d, Eigen::aligned_allocator< Eigen::Matrix4d > > frames)
void handleNewTransformationData (Transformation_Data &data)
void init (boost::shared_ptr< MarkerPublisher > markerManager, boost::shared_ptr< Calibration_Object > calibrationObject, boost::shared_ptr< Transformation_Publisher > transformationPublisher, const Eigen::Matrix4d calObjTransformation)
bool markerPoseWithinBounds (const Eigen::Matrix4d &transform)
void resizeEvent (QResizeEvent *event)
void setUI_Elements ()
void startCapture ()
void stopMarkerCapturing ()

Private Attributes

QPushButton * btnExportCameraOffset
QPushButton * btnExportCameraPoses
QPushButton * btnExportRelativeMarkerPoses
QPushButton * btnSkipFramePTUSearch
QPushButton * btnStartStopPTUSearch
boost::shared_ptr
< Calibration_Object
calibrationObject
CameraWidgetcameraLeft
PanTiltOffsetTupleList cameraOffsetParameters
CameraWidgetcameraRight
std::vector
< colouredCameraFrame,
Eigen::aligned_allocator
< colouredCameraFrame > > 
colouredCameraFrames
QLabel * lblCameraFrameCount
QLabel * lblRelativeMarkerFrameCount
double marker_max_distance
double marker_min_distance
std::vector< Eigen::Matrix4d,
Eigen::aligned_allocator
< Eigen::Matrix4d > > 
markerLeftPoses
Marker_ManagermarkerManager
boost::shared_ptr
< MarkerPublisher
markerPublisher
std::vector< Eigen::Matrix4d,
Eigen::aligned_allocator
< Eigen::Matrix4d > > 
markerRightPoses
tf::TransformListener * mTFlistener
double pan_max_angle
double pan_min_angle
PTU_ManagerptuManager
std::vector< Eigen::Matrix4d,
Eigen::aligned_allocator
< Eigen::Matrix4d > > 
relativeMarkerPoses
bool slotEnabled_Marker
bool slotEnabled_PTU
bool stopSignal
std::vector< Eigen::Matrix4d,
Eigen::aligned_allocator
< Eigen::Matrix4d > > 
tempMarkerLeftPoses
std::vector< Eigen::Matrix4d,
Eigen::aligned_allocator
< Eigen::Matrix4d > > 
tempMarkerRightPoses
std::vector< Transformation_DatatempTransformationData
double tilt_max_angle
double tilt_min_angle
Eigen::Matrix4d transformation_LaserScanner
std::vector< Transformation_DatatransformationData
boost::shared_ptr
< Transformation_Publisher
transformationPublisher
bool useAveragedMarkerData

Detailed Description

Copyright (c) 2016, Aumann Florian, Heller Florian, Meißner Pascal All rights reserved.

Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:

1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.

2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.

3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.

THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

Definition at line 47 of file ptuwindow.h.


Constructor & Destructor Documentation

PTUWindow::PTUWindow ( QWidget *  parent = 0) [explicit]

Copyright (c) 2016, Aumann Florian, Heller Florian, Meißner Pascal All rights reserved.

Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:

1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.

2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.

3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.

THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

Definition at line 24 of file ptuwindow.cpp.

PTUWindow::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 
)

Definition at line 33 of file ptuwindow.cpp.


Member Function Documentation

Definition at line 213 of file ptuwindow.cpp.

Definition at line 228 of file ptuwindow.cpp.

Definition at line 242 of file ptuwindow.cpp.

Definition at line 187 of file ptuwindow.cpp.

Definition at line 195 of file ptuwindow.cpp.

Definition at line 471 of file ptuwindow.cpp.

Eigen::Matrix4d PTUWindow::calculateAverageDataFrame ( std::vector< Eigen::Matrix4d, Eigen::aligned_allocator< Eigen::Matrix4d > >  frames) [private]

Definition at line 503 of file ptuwindow.cpp.

Definition at line 290 of file ptuwindow.cpp.

void PTUWindow::init ( boost::shared_ptr< MarkerPublisher markerManager,
boost::shared_ptr< Calibration_Object calibrationObject,
boost::shared_ptr< Transformation_Publisher transformationPublisher,
const Eigen::Matrix4d  calObjTransformation 
) [private]

Definition at line 39 of file ptuwindow.cpp.

void PTUWindow::markerFound ( std::string  markerNumber,
const Eigen::Matrix4d &  transformation 
) [slot]

Definition at line 307 of file ptuwindow.cpp.

bool PTUWindow::markerPoseWithinBounds ( const Eigen::Matrix4d &  transform) [private]

Definition at line 528 of file ptuwindow.cpp.

void PTUWindow::newTransform_Camera ( const Eigen::Matrix4d &  transform,
Markertype  markertype 
) [signal]
void PTUWindow::ptu_moved ( double  pan,
double  tilt 
) [slot]

Definition at line 551 of file ptuwindow.cpp.

void PTUWindow::resizeEvent ( QResizeEvent *  event) [private]

Definition at line 171 of file ptuwindow.cpp.

void PTUWindow::setUI_Elements ( ) [private]

Definition at line 142 of file ptuwindow.cpp.

void PTUWindow::startCapture ( ) [private]

Definition at line 256 of file ptuwindow.cpp.

void PTUWindow::stopMarkerCapturing ( ) [private]

Definition at line 432 of file ptuwindow.cpp.


Member Data Documentation

QPushButton* PTUWindow::btnExportCameraOffset [private]

Definition at line 68 of file ptuwindow.h.

QPushButton* PTUWindow::btnExportCameraPoses [private]

Definition at line 66 of file ptuwindow.h.

Definition at line 67 of file ptuwindow.h.

QPushButton* PTUWindow::btnSkipFramePTUSearch [private]

Definition at line 65 of file ptuwindow.h.

QPushButton* PTUWindow::btnStartStopPTUSearch [private]

Definition at line 64 of file ptuwindow.h.

boost::shared_ptr<Calibration_Object> PTUWindow::calibrationObject [private]

Definition at line 99 of file ptuwindow.h.

Definition at line 73 of file ptuwindow.h.

Definition at line 114 of file ptuwindow.h.

Definition at line 74 of file ptuwindow.h.

std::vector<colouredCameraFrame, Eigen::aligned_allocator<colouredCameraFrame> > PTUWindow::colouredCameraFrames [private]

Definition at line 102 of file ptuwindow.h.

QLabel* PTUWindow::lblCameraFrameCount [private]

Definition at line 70 of file ptuwindow.h.

Definition at line 71 of file ptuwindow.h.

Definition at line 87 of file ptuwindow.h.

Definition at line 86 of file ptuwindow.h.

std::vector<Eigen::Matrix4d , Eigen::aligned_allocator<Eigen::Matrix4d > > PTUWindow::markerLeftPoses [private]

Definition at line 109 of file ptuwindow.h.

Definition at line 62 of file ptuwindow.h.

boost::shared_ptr<MarkerPublisher> PTUWindow::markerPublisher [private]

Definition at line 84 of file ptuwindow.h.

std::vector<Eigen::Matrix4d , Eigen::aligned_allocator<Eigen::Matrix4d > > PTUWindow::markerRightPoses [private]

Definition at line 108 of file ptuwindow.h.

tf::TransformListener* PTUWindow::mTFlistener [private]

Definition at line 93 of file ptuwindow.h.

double PTUWindow::pan_max_angle [private]

Definition at line 91 of file ptuwindow.h.

double PTUWindow::pan_min_angle [private]

Definition at line 90 of file ptuwindow.h.

Definition at line 61 of file ptuwindow.h.

std::vector<Eigen::Matrix4d , Eigen::aligned_allocator<Eigen::Matrix4d > > PTUWindow::relativeMarkerPoses [private]

Definition at line 107 of file ptuwindow.h.

Definition at line 77 of file ptuwindow.h.

Definition at line 76 of file ptuwindow.h.

bool PTUWindow::stopSignal [private]

Definition at line 78 of file ptuwindow.h.

std::vector<Eigen::Matrix4d , Eigen::aligned_allocator<Eigen::Matrix4d > > PTUWindow::tempMarkerLeftPoses [private]

Definition at line 112 of file ptuwindow.h.

std::vector<Eigen::Matrix4d , Eigen::aligned_allocator<Eigen::Matrix4d > > PTUWindow::tempMarkerRightPoses [private]

Definition at line 111 of file ptuwindow.h.

Definition at line 105 of file ptuwindow.h.

double PTUWindow::tilt_max_angle [private]

Definition at line 89 of file ptuwindow.h.

double PTUWindow::tilt_min_angle [private]

Definition at line 88 of file ptuwindow.h.

Eigen::Matrix4d PTUWindow::transformation_LaserScanner [private]

Definition at line 101 of file ptuwindow.h.

Definition at line 103 of file ptuwindow.h.

Definition at line 96 of file ptuwindow.h.

Definition at line 81 of file ptuwindow.h.


The documentation for this class was generated from the following files:


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