transformation_publisher.h
Go to the documentation of this file.
1 
18 #ifndef TRANSFORMATION_PUBLISHER_H
19 #define TRANSFORMATION_PUBLISHER_H
20 #include <QThread>
21 
22 #include <calibration_object.h>
23 
24 #ifndef Q_MOC_RUN
25 #include <sensor_msgs/JointState.h>
26 #include <tf/transform_broadcaster.h>
27 #include <Eigen/Dense>
28 #include <ros/ros.h>
29 #include <ros/init.h>
30 #include <boost/shared_ptr.hpp>
31 #endif
32 
34 {
37 };
38 
39 class Transformation_Publisher : public QThread
40 {
41  Q_OBJECT
42 public:
44 
45  void stop();
46  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
47 protected:
48 
51  tf::TransformBroadcaster broadcaster;
52 
53  std::vector<geometry_msgs::TransformStamped> staticTransforms;
54  geometry_msgs::TransformStamped mapToTop;
55  geometry_msgs::TransformStamped topToScanFrame;
56  geometry_msgs::TransformStamped markerLeftToCamera;
57  geometry_msgs::TransformStamped markerRightToCamera;
58 
60 
61  void run();
62  geometry_msgs::Transform matrixToTransform(const Eigen::Matrix4d& matrix);
63 
64 public slots:
65  void newTransform_Laserscan(const Eigen::Matrix4d& transform, double distanceToTop);
66  void newTransform_Camera(const Eigen::Matrix4d& transform, Markertype markertype);
67 };
68 
69 
70 #endif // TRANSFORMATION_PUBLISHER_H
geometry_msgs::TransformStamped markerRightToCamera
Transformation_Publisher(boost::shared_ptr< Calibration_Object > object)
void newTransform_Camera(const Eigen::Matrix4d &transform, Markertype markertype)
void newTransform_Laserscan(const Eigen::Matrix4d &transform, double distanceToTop)
geometry_msgs::TransformStamped markerLeftToCamera
tf::TransformBroadcaster broadcaster
geometry_msgs::TransformStamped topToScanFrame
geometry_msgs::Transform matrixToTransform(const Eigen::Matrix4d &matrix)
std::vector< geometry_msgs::TransformStamped > staticTransforms
geometry_msgs::TransformStamped mapToTop


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