NimbRo ROS Soccer Package
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Groups Pages
frameview.h
1 #ifndef FRAMEVIEW_H
2 #define FRAMEVIEW_H
3 
4 // Widget to edit propertirs of KeyFrame:
5 // Duration
6 // Efforts
7 
8 // Author: Dmytro Pavlichenko <dm.mark999@gmail.com>
9 
10 #include <QWidget>
11 #include <QObject>
12 
13 #include <boost/shared_ptr.hpp>
14 #include <motion_file/motionfile.h>
15 
16 #include <ros/node_handle.h>
17 #include <ros/subscriber.h>
18 
19 #include <robotcontrol/RobotState.h>
20 
21 namespace Ui
22 {
23  class FrameView;
24 }
25 
26 // TODO refactor
27 class FrameView : public QWidget
28 {
29 Q_OBJECT
30 public:
31  typedef boost::shared_ptr<motionfile::Keyframe> KeyframePtr;
32 
33  FrameView(QWidget *parent = 0);
34  ~FrameView();
35 
36  virtual bool eventFilter(QObject *object, QEvent *event);
37 
38  QString getPathToDir(); // Return path to dirrectory where current motion file is located
39 
40  double getEffort();
41  int nameToIndex(std::string name);
42 
43  static bool parseSupport(QString support, double &left, double &right);
44 
45 Q_SIGNALS:
46  void updateFrame();
47  void frameLoaded(KeyframePtr frame);
48  void changeEffortForAllFrames(std::vector<int> indexesToApply, double newEffort);
49 
50 public Q_SLOTS:
51  void saveFrame(); // Saves current frame near opened motion with ".frame" extension
52  void loadFrame();
53 
54  void setFrame(KeyframePtr frame);
55  void updateJointList(const std::vector<std::string> &jointList);
56 
57  void setPathAndName(QString path); // Extracts path to file and file name for further saving
58 
59 private Q_SLOTS:
60  void nameChanged();
61  void updateRollPitchYaw();
62 
63  void durationSpinChanged();
64  void durationSliderChanged();
65 
66  void enableSupport(bool enable);
67 
68  void supportLeftSpinChanged();
69  void supportRightSpinChanged();
70  void supportSliderChanged();
71 
72  void handleRollSpinChanged();
73  void handlePitchSpinChanged();
74  void handleYawSpinChanged();
75 
76  void changeEffort();
77  void setAllChecked(bool flag);
78 
79 private:
80  void findIndices(std::vector<int> &indices);
81  void setCurrentSupport(); // Set support from spins
82  void setSupportFromFrame(); // Parse support from frame, set sliders/spins
83 
84  void robotStateReceived(const robotcontrol::RobotStateConstPtr& state);
85 
86 private:
87  Ui::FrameView *ui;
88 
89  KeyframePtr frame;
90  std::vector<std::string> joints;
91 
92  QString path;
93  QString motionName;
94 
95  ros::NodeHandle nh;
96  ros::Subscriber subscriber;
97  bool updateRPY; // If true, values of Roll,Pitch,Yaw from /robotmodel/robot_state are set to current frame
98 };
99 
100 #endif // FRAMEVIEW_H