path_planning.hpp
Go to the documentation of this file.
1 #ifndef RAM_QT_GUIS_PATH_PLANNING_HPP
2 #define RAM_QT_GUIS_PATH_PLANNING_HPP
3 
4 #ifndef Q_MOC_RUN
13 #include <ros/package.h>
14 #include <ros/ros.h>
15 #include <ros/service.h>
16 #include <rviz/panel.h>
17 
19 #include <ram_path_planning/ContoursAction.h>
20 #include <ram_path_planning/DonghongDingAction.h>
21 #include <ram_path_planning/FollowPosesAction.h>
22 #endif
23 
24 #include <QComboBox>
25 #include <QDoubleSpinBox>
26 #include <QFileDialog>
27 #include <QHBoxLayout>
28 #include <QLabel>
29 #include <QLayout>
30 #include <QLineEdit>
31 #include <QMessageBox>
32 #include <QPushButton>
33 #include <QScrollArea>
34 #include <QStackedWidget>
35 #include <QtConcurrent/QtConcurrentRun>
36 
37 namespace ram_qt_guis
38 {
39 class PathPlanning : public rviz::Panel
40 {
41 Q_OBJECT
42 
43 public:
44  PathPlanning(QWidget* parent = NULL);
45  virtual ~PathPlanning();
46 
47 Q_SIGNALS:
48  void displayErrorMessageBox(const QString,
49  const QString,
50  const QString);
51 
52 protected Q_SLOTS:
53  void addAlgorithmsToGUI();
54  void algorithmChanged();
55 
58  const ram_path_planning::DonghongDingResultConstPtr &result);
59  void donghongDingFeedbackCb(const ram_path_planning::DonghongDingFeedbackConstPtr &feedback);
60 
61  void contoursButtonHandler();
63  const ram_path_planning::ContoursResultConstPtr &result);
64  void contoursFeedbackCb(const ram_path_planning::ContoursFeedbackConstPtr &feedback);
65 
68  const ram_path_planning::FollowPosesResultConstPtr &result);
69  void FollowPosesFeedbackCb(const ram_path_planning::FollowPosesFeedbackConstPtr &feedback);
70 
71  void displayErrorBoxHandler(const QString title,
72  const QString message,
73  const QString info_msg);
74 
75  void load(const rviz::Config& config);
76  void save(rviz::Config config) const;
77 
78 private:
79  void connectToActions();
80 
81  std::shared_ptr<ProgressDialog> progress_dialog_;
82 
84 
85  QStackedWidget * algorithm_stacked_widget_;
87 
88  QComboBox *select_algorithm_;
90  std::vector<std::string> algorithm_descriptions_;
91  unsigned loaded_last_algorithm_ = 0;
92 
96 
97  // Action clients
101 
102  std::unique_ptr<DonghongDingActionClient> donghong_ding_ac_;
103  std::unique_ptr<ContoursActionClient> contours_ac_;
104  std::unique_ptr<FollowPosesActionClient> follow_poses_ac_;
105 
106  // Goals
107  ram_path_planning::DonghongDingGoal donghong_ding_goal_;
108  ram_path_planning::ContoursGoal contours_goal_;
109  ram_path_planning::FollowPosesGoal follow_poses_goal_;
110 
111 };
112 
113 }
114 
115 #endif
#define NULL
void contoursDoneCb(const actionlib::SimpleClientGoalState &state, const ram_path_planning::ContoursResultConstPtr &result)
void contoursFeedbackCb(const ram_path_planning::ContoursFeedbackConstPtr &feedback)
actionlib::SimpleActionClient< ram_path_planning::ContoursAction > ContoursActionClient
config
void FollowPosesFeedbackCb(const ram_path_planning::FollowPosesFeedbackConstPtr &feedback)
ContoursWidget * contours_ui_
void displayErrorBoxHandler(const QString title, const QString message, const QString info_msg)
QPushButton * generate_trajectory_button_
void donghongDingDoneCb(const actionlib::SimpleClientGoalState &state, const ram_path_planning::DonghongDingResultConstPtr &result)
actionlib::SimpleActionClient< ram_path_planning::DonghongDingAction > DonghongDingActionClient
std::shared_ptr< ProgressDialog > progress_dialog_
void FollowPosesDoneCb(const actionlib::SimpleClientGoalState &state, const ram_path_planning::FollowPosesResultConstPtr &result)
std::unique_ptr< ContoursActionClient > contours_ac_
void displayErrorMessageBox(const QString, const QString, const QString)
void load(const rviz::Config &config)
std::vector< std::string > algorithm_descriptions_
ram_path_planning::DonghongDingGoal donghong_ding_goal_
actionlib::SimpleActionClient< ram_path_planning::FollowPosesAction > FollowPosesActionClient
ram_path_planning::FollowPosesGoal follow_poses_goal_
std::unique_ptr< DonghongDingActionClient > donghong_ding_ac_
std::unique_ptr< FollowPosesActionClient > follow_poses_ac_
void save(rviz::Config config) const
ram_path_planning::ContoursGoal contours_goal_
PathPlanning(QWidget *parent=NULL)
void donghongDingFeedbackCb(const ram_path_planning::DonghongDingFeedbackConstPtr &feedback)
DonghongDingWidget * donghong_ding_ui_
FollowPosesWidget * follow_poses_ui_
QStackedWidget * algorithm_stacked_widget_


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