pose_info.hpp
Go to the documentation of this file.
1 #ifndef RAM_QT_GUIS_POSE_INFO_HPP
2 #define RAM_QT_GUIS_POSE_INFO_HPP
3 
4 #ifndef Q_MOC_RUN
6 #include <mutex>
7 #include <ram_modify_trajectory/GetPosesFromTrajectory.h>
8 #include <ram_msgs/AdditiveManufacturingTrajectory.h>
9 #include <ros/ros.h>
10 #include <rviz/panel.h>
11 #endif
12 
13 #include <QDateTime>
14 #include <QHBoxLayout>
15 #include <QLabel>
16 #include <QMessageBox>
17 #include <QPushButton>
18 #include <QScrollArea>
19 #include <QSpinBox>
20 #include <QVBoxLayout>
21 #include <QtConcurrent/QtConcurrentRun>
22 
23 namespace ram_qt_guis
24 {
25 class PoseInfo : public rviz::Panel
26 {
27 Q_OBJECT
28  public:
29  PoseInfo(QWidget* parent = NULL);
30  virtual ~PoseInfo();
31 
32  void connectToServices();
33  void checkForPublishers();
34  void trajectoryCallback(const ram_msgs::AdditiveManufacturingTrajectoryConstPtr&);
35 
36 protected Q_SLOTS:
37  void backButtonHandler();
38  void forwardButtonHandler();
40  void lastPoseButtonHandler();
41  void getPoseInformation();
42  void updateGUIparameters();
43 
44  void load(const rviz::Config& config);
45  void save(rviz::Config config) const;
46 
47 protected:
48  unsigned trajectory_size_;
49 
50  // Geometric pose
51  QLabel *x_;
52  QLabel *y_;
53  QLabel *z_;
54  QLabel *w_;
55  QLabel *p_;
56  QLabel *r_;
57 
58  // Info
59  QLabel *layers_level_;
60  QLabel *layer_index_;
61  QLabel *polygon_start_;
62  QLabel *polygon_end_;
63  QLabel *entry_pose_;
64  QLabel *exit_pose_;
65 
66  // Parameters
67  QLabel *movement_type_;
68  QLabel *approach_type_;
69  QLabel *blend_radius_;
70  QLabel *speed_;
71  QLabel *laser_power_;
72  QLabel *feed_rate_;
73 
74  // Buttons
75  QPushButton *back_button_;
76  QPushButton *forward_button_;
77  QPushButton *first_pose_button_;
78  QPushButton *last_pose_button_;
79 
80  // Index
81  QSpinBox *pose_index_;
82 
83  // ROS
87  std::recursive_mutex pose_params_mutex_;
88  ram_modify_trajectory::GetPosesFromTrajectory pose_params_;
89 };
90 
91 }
92 
93 #endif
#define NULL
QSpinBox * pose_index_
Definition: pose_info.hpp:81
ram_modify_trajectory::GetPosesFromTrajectory pose_params_
Definition: pose_info.hpp:88
ros::Subscriber trajectory_sub_
Definition: pose_info.hpp:86
PoseInfo(QWidget *parent=NULL)
Definition: pose_info.cpp:6
void save(rviz::Config config) const
Definition: pose_info.cpp:313
config
QPushButton * last_pose_button_
Definition: pose_info.hpp:78
ros::NodeHandle nh_
Definition: pose_info.hpp:84
std::recursive_mutex pose_params_mutex_
Definition: pose_info.hpp:87
ros::ServiceClient get_poses_from_trajectory_client_
Definition: pose_info.hpp:85
QPushButton * first_pose_button_
Definition: pose_info.hpp:77
unsigned trajectory_size_
Definition: pose_info.hpp:48
void trajectoryCallback(const ram_msgs::AdditiveManufacturingTrajectoryConstPtr &)
Definition: pose_info.cpp:157
QPushButton * forward_button_
Definition: pose_info.hpp:76
void load(const rviz::Config &config)
Definition: pose_info.cpp:302
QPushButton * back_button_
Definition: pose_info.hpp:75


ram_qt_guis
Author(s): Victor Lamoine - Institut Maupertuis
autogenerated on Mon Jun 10 2019 14:50:11