27 #include <QPushButton> 35 #include <sensor_msgs/Image.h> 36 #include <Eigen/Dense> 37 #include <boost/shared_ptr.hpp> 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> 53 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
60 Eigen::Matrix4d
calculateAverageDataFrame(std::vector<Eigen::Matrix4d , Eigen::aligned_allocator<Eigen::Matrix4d > > frames);
108 std::vector<Eigen::Matrix4d , Eigen::aligned_allocator<Eigen::Matrix4d > >
markerRightPoses;
109 std::vector<Eigen::Matrix4d , Eigen::aligned_allocator<Eigen::Matrix4d > >
markerLeftPoses;
128 void markerFound(std::string markerNumber,
const Eigen::Matrix4d &transformation);
131 #endif // PTUWINDOW_H
std::vector< Eigen::Matrix4d, Eigen::aligned_allocator< Eigen::Matrix4d > > markerRightPoses
std::vector< Eigen::Matrix4d, Eigen::aligned_allocator< Eigen::Matrix4d > > tempMarkerLeftPoses
CameraWidget * cameraRight
std::vector< Eigen::Matrix4d, Eigen::aligned_allocator< Eigen::Matrix4d > > markerLeftPoses
QPushButton * btnExportCameraOffset
std::vector< Transformation_Data > tempTransformationData
double marker_max_distance
double marker_min_distance
bool markerPoseWithinBounds(const Eigen::Matrix4d &transform)
void resizeEvent(QResizeEvent *event)
void btnSkipFramePTUSearch_clicked()
boost::shared_ptr< MarkerPublisher > markerPublisher
std::vector< colouredCameraFrame, Eigen::aligned_allocator< colouredCameraFrame > > colouredCameraFrames
boost::shared_ptr< Transformation_Publisher > transformationPublisher
void stopMarkerCapturing()
tf::TransformListener * mTFlistener
void btnExportRelativeMarkerPoses_clicked()
QLabel * lblRelativeMarkerFrameCount
Marker_Manager * markerManager
PTUWindow(QWidget *parent=0)
QPushButton * btnSkipFramePTUSearch
void markerFound(std::string markerNumber, const Eigen::Matrix4d &transformation)
std::vector< Eigen::Matrix4d, Eigen::aligned_allocator< Eigen::Matrix4d > > relativeMarkerPoses
PanTiltOffsetTupleList cameraOffsetParameters
void newTransform_Camera(const Eigen::Matrix4d &transform, Markertype markertype)
QPushButton * btnExportCameraPoses
void btnExportCameraPoses_clicked()
void handleNewTransformationData(Transformation_Data &data)
std::vector< Transformation_Data > transformationData
CameraWidget * cameraLeft
Eigen::Matrix4d calculateAverageDataFrame(std::vector< Eigen::Matrix4d, Eigen::aligned_allocator< Eigen::Matrix4d > > frames)
std::vector< Eigen::Matrix4d, Eigen::aligned_allocator< Eigen::Matrix4d > > tempMarkerRightPoses
void btnStartStopPTUSearch_clicked()
void ptu_moved(double pan, double tilt)
QPushButton * btnExportRelativeMarkerPoses
QPushButton * btnStartStopPTUSearch
QLabel * lblCameraFrameCount
void init(boost::shared_ptr< MarkerPublisher > markerManager, boost::shared_ptr< Calibration_Object > calibrationObject, boost::shared_ptr< Transformation_Publisher > transformationPublisher, const Eigen::Matrix4d calObjTransformation)
boost::shared_ptr< Calibration_Object > calibrationObject
void calculateAllAverageDataFrames()
bool useAveragedMarkerData
void btnExportCameraOffset_clicked()
Eigen::Matrix4d transformation_LaserScanner