path_planning_widget.h
Go to the documentation of this file.
1 #ifndef PATH_PLANNING_WIDGET_H
2 #define PATH_PLANNING_WIDGET_H
3 
4 #ifndef Q_MOC_RUN
5 #include <ros/ros.h>
6 #include <ros/service.h>
7 #include <rviz/panel.h>
8 #include <std_msgs/String.h>
9 #include <fanuc_grinding_path_planning/PathPlanningService.h>
10 #endif
11 
12 class QLabel;
13 class QRadioButton;
14 class QPushButton;
15 class QMessageBox;
16 class QCheckBox;
17 class QSpinBox;
18 class QDoubleSpinBox;
19 
21 {
22 class PathPlanningWidget : public QWidget
23 {
24  Q_OBJECT
25 public:
26  PathPlanningWidget(QWidget* parent = NULL);
27  void load(const rviz::Config& config);
28  void save(rviz::Config config);
29  void setPathPlanningParams(fanuc_grinding_path_planning::PathPlanningService::Request &params);
30  std::vector<geometry_msgs::Pose> getRobotPoses();
31  std::vector<bool> getIsGrindingPose();
32 
33 Q_SIGNALS:
34  void guiChanged();
35  void sendStatus(QString status);
36  void sendMsgBox(QString title, QString msg, QString info_msg);
37  void enablePanel(bool);
41  void getCADAndScanParams();
42 
43 protected Q_SLOTS:
44  void connectToServices();
45  void triggerSave();
46  void updateGUI();
47  void updateInternalValues();
48  void newStatusMessage(const std_msgs::String::ConstPtr &msg);
51  void pathPlanningService();
56  void setDepthOfPassEnable(const int state);
57  void setCADAndScanParams(const QString cad_filename,
58  const QString scan_filename);
59 
60 protected:
63  fanuc_grinding_path_planning::PathPlanningService srv_path_planning_;
65 
66  QCheckBox* surfacing_mode_;
68  QDoubleSpinBox* depth_of_pass_;
71  QDoubleSpinBox* grinder_width_;
72  QRadioButton* lean_angle_axis_x_;
73  QRadioButton* lean_angle_axis_y_;
74  QRadioButton* lean_angle_axis_z_;
75  QDoubleSpinBox* angle_value_;
76  QPushButton* compute_trajectory_;
77  QDoubleSpinBox* trajectory_z_offset_;
78  QPushButton* execute_trajectory_;
79 };
80 
81 } // End namespace
82 
83 #endif // PATH_PLANNING_WIDGET_H
#define NULL
void newStatusMessage(const std_msgs::String::ConstPtr &msg)
void setCADAndScanParams(const QString cad_filename, const QString scan_filename)
fanuc_grinding_path_planning::PathPlanningService srv_path_planning_
void setPathPlanningParams(fanuc_grinding_path_planning::PathPlanningService::Request &params)
void sendMsgBox(QString title, QString msg, QString info_msg)
config
std::vector< geometry_msgs::Pose > getRobotPoses()


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