rqt_play_motion_builder.h
Go to the documentation of this file.
1 #ifndef RQT_MOTION_BUILDER_H
2 #define RQT_MOTION_BUILDER_H
3 
4 #include <rqt_gui_cpp/plugin.h>
5 #include <ui_rqt_play_motion_builder.h>
7 
8 #include <play_motion_builder_msgs/BuildMotionAction.h>
9 #include <play_motion_builder_msgs/EditMotion.h>
10 #include <play_motion_builder_msgs/RunMotionAction.h>
11 
13 
14 #include <QMenu>
15 
16 namespace pal
17 {
19 {
20  Q_OBJECT
21 public:
23 
24  virtual void initPlugin(qt_gui_cpp::PluginContext& context) override;
25  virtual void shutdownPlugin() override;
26  virtual void saveSettings(qt_gui_cpp::Settings&, qt_gui_cpp::Settings&) const override
27  {
28  }
29  virtual void restoreSettings(const qt_gui_cpp::Settings&, const qt_gui_cpp::Settings&) override
30  {
31  }
32 
33 private:
36 
37  Ui::MotionBuilder ui_;
38  QWidget* widget_;
39  QMenu table_menu_;
41 
42  std::unique_ptr<BMAC> builder_client_;
43  std::unique_ptr<RMAC> run_motion_client_;
47 
48  const static std::string GOTO_MENU;
49  const static std::string DELETE_MENU;
50  const static std::string SET_TO_CURRENT_MENU;
51  const static std::string COPY_BELOW_MENU;
52  const static std::string COPY_LAST_MENU;
53 
54  bool editing_;
57  std::string editing_motion_;
58 
59  void loadMotion(const play_motion_builder_msgs::Motion& motion);
60  double getJointPosition(const std::vector<std::string>& joints,
61  const std::vector<double>& poses, const std::string& joint_header);
62  void listMotion();
63  void enableBtns();
64  void disableBtns();
65  void runDone(const actionlib::SimpleClientGoalState& state,
66  const play_motion_builder_msgs::RunMotionResultConstPtr& result);
67 
68 private slots:
69  void onNewPressed();
70  void onLoadPressed();
71  void onCaptureClicked();
72  void onPlayClicked();
73  void onSaveClicked();
74  void onContextMenuRequested(const QPoint& point);
75  void onGotoSelected(int frame);
76  void onDeleteSelected(int frame);
77  void onSetToCurrentSelected(int frame);
78  void onCopyBelowSelected(int frame);
79  void onCopyLastSelected(int frame);
80  void onGroupToggled(bool state);
81  void onJointToggled(bool state);
82  void onCellChanged(int row, int col);
83  void onMotionStored(QString motion_name);
84 
85 signals:
86  void goToSelected(int row);
87  void deleteSelected(int row);
88  void setToCurrentSelected(int row);
89  void copyBelowSelected(int row);
90  void copyLastSelected(int row);
91 };
92 } // namespace pal
93 
94 #endif /* RQT_MOTION_BUILDER_H */
void loadMotion(const play_motion_builder_msgs::Motion &motion)
ros::ServiceClient edit_motion_client_
void copyLastSelected(int row)
std::unique_ptr< BMAC > builder_client_
static const std::string DELETE_MENU
actionlib::SimpleActionClient< play_motion_builder_msgs::RunMotionAction > RMAC
static const std::string COPY_LAST_MENU
actionlib::SimpleActionClient< play_motion_builder_msgs::BuildMotionAction > BMAC
virtual void initPlugin(qt_gui_cpp::PluginContext &context) override
std::unique_ptr< RMAC > run_motion_client_
ros::ServiceClient change_joints_client_
void setToCurrentSelected(int row)
void onMotionStored(QString motion_name)
void goToSelected(int row)
ros::ServiceClient list_joints_client_
virtual void shutdownPlugin() override
void runDone(const actionlib::SimpleClientGoalState &state, const play_motion_builder_msgs::RunMotionResultConstPtr &result)
void onContextMenuRequested(const QPoint &point)
double getJointPosition(const std::vector< std::string > &joints, const std::vector< double > &poses, const std::string &joint_header)
static const std::string SET_TO_CURRENT_MENU
void deleteSelected(int row)
static const std::string GOTO_MENU
void onCellChanged(int row, int col)
virtual void saveSettings(qt_gui_cpp::Settings &, qt_gui_cpp::Settings &) const override
static const std::string COPY_BELOW_MENU
MotionProperties * properties_dialog_
virtual void restoreSettings(const qt_gui_cpp::Settings &, const qt_gui_cpp::Settings &) override
void copyBelowSelected(int row)


rqt_play_motion_builder
Author(s):
autogenerated on Mon Feb 28 2022 23:13:41