post_processor_widget.h
Go to the documentation of this file.
1 #ifndef POST_PROCESSOR_WIDGET_H
2 #define POST_PROCESSOR_WIDGET_H
3 
4 #ifndef Q_MOC_RUN
5 #include <ros/ros.h>
6 #include <ros/package.h>
7 #include <ros/service.h>
8 #include <rviz/panel.h>
9 #include <fanuc_grinding_post_processor/PostProcessorService.h>
10 #endif
11 
12 class QLabel;
13 class QLineEdit;
14 class QPushButton;
15 class QCheckBox;
16 class QSpinBox;
17 
19 {
20 class PostProcessorWidget : public QWidget
21 {
22  Q_OBJECT
23 public:
24  PostProcessorWidget(QWidget* parent = NULL);
25  void load(const rviz::Config& config);
26  void save(rviz::Config config);
27  void setPostProcessorParams(const fanuc_grinding_post_processor::PostProcessorService::Request &params);
28  void setProgramLocation(const std::string &location);
29  void setRobotPoses(const std::vector<geometry_msgs::Pose> &robot_poses);
30  void setIsGrindingPose(const std::vector<bool> &is_grinding_pose);
31 
32 Q_SIGNALS:
33  void guiChanged();
34  void sendStatus(const QString status);
35  void sendMsgBox(const QString title, const QString msg, const QString info_msg);
36  void enablePanel(const bool);
38 
39 protected Q_SLOTS:
40  void connectToServices();
41  void triggerSave();
42  void updateGUI();
43  void updateInternalValues();
45  void generateProgram();
46  void tweakProgramName();
47  void setIpAddressEnable(const int state);
48 
49 protected:
52  fanuc_grinding_post_processor::PostProcessorService srv_post_processor_;
53 
54  QLineEdit* program_name_;
55  QLineEdit* comment_;
56  QSpinBox* machining_speed_;
57  QSpinBox* extrication_speed_;
59  QCheckBox* upload_program_;
61  QLineEdit* ip_address_;
62  QLineEdit* program_location_;
64 };
65 
66 } // End namespace
67 
68 #endif // POST_PROCESSOR_WIDGET_H
#define NULL
void setRobotPoses(const std::vector< geometry_msgs::Pose > &robot_poses)
void sendMsgBox(const QString title, const QString msg, const QString info_msg)
config
fanuc_grinding_post_processor::PostProcessorService srv_post_processor_
void setIsGrindingPose(const std::vector< bool > &is_grinding_pose)
void setProgramLocation(const std::string &location)
void setPostProcessorParams(const fanuc_grinding_post_processor::PostProcessorService::Request &params)


rviz_plugin
Author(s): Kévin Bolloré, Victor Lamoine - Institut Maupertuis
autogenerated on Thu Dec 19 2019 03:38:28