NimbRo ROS Soccer Package
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Groups Pages
keyframemodel.h
1 // Handles operations on keyframes
2 // Authors: Max Schwarz <max.schwarz@uni-bonn.de>, Dmytro Pavlichenko <dm.mark999@gmail.com>
3 
4 #ifndef KEYFRAME_MODEL_H
5 #define KEYFRAME_MODEL_H
6 
7 #include <QAbstractListModel>
8 #include <QItemSelection>
9 
10 #include <motion_file/motionfile.h>
11 
12 #include <trajectory_editor/jointperspective.h>
13 #include <trajectory_editor/robotdisplay.h>
14 #include <trajectory_editor/headerview.h>
15 
16 class KeyframeModel : public QAbstractListModel
17 {
18 Q_OBJECT
19 public:
20  typedef boost::shared_ptr<motionfile::Keyframe> KeyframePtr;
21 
22  explicit KeyframeModel(QObject* parent = 0);
23  virtual ~KeyframeModel();
24 
25  int rowCount(const QModelIndex &parent = QModelIndex()) const;
26 
27  void removeFrame(unsigned position);
28  void moveFrame(unsigned position, int direction); // Move frame from position by +1/-1 within the vector
29 
30  void copySelectedFrames(QModelIndexList selectedIndexes);
31  void insertCopiedFrames();
32 
33  void setSaved();
34  void setMotion(motionfile::Motion motion);
35 
36  joint_perspective::PerspectiveManager* getPerspectiveManager();
37 
38  KeyframePtr getCurrentFrameCopy();
39 
40  motionfile::Motion& getMotion();
41  motionfile::Motion getMotionCopy();
42  std::vector<std::string> getJointList();
43 
44  bool hasMotion();
45  bool hasUnsavedChanges();
46 
47 Q_SIGNALS:
48  void setViewSelection(int row);
49  void setViewSelection(QItemSelection selection);
50  void updateCurrentFileLabel(QString newTitle);
51 
52  void currentFrameChanged(KeyframePtr frame);
53  void jointListChanged(std::vector<std::string> list);
54  void perspectiveChanged(const joint_perspective::JointPerspective& perspective);
55 
56  void headerDataChanged(HeaderData);
57 
58  void gotMotion(bool); // Emmited when model got motion
59  void gotRules(const std::vector<motionfile::Rule> &rules);
60 
61  void updateRobot(std::vector<std::string> &joint_list, std::vector<double> &joint_positions);
62  void modelChanged(std::string model_path);
63 
64  void getInverseLimits(bool &limit, double &epsilon);
65 
66 public Q_SLOTS:
67  void addFrame(int row);
68  void showMotionInFolder(); // Show current motion file in folder
69 
70  void updateHeaderData(HeaderData); // Update name, states, etc
71  void updateRobotDisplay();
72 
73  void handleIndexChange(const QModelIndex& index);
74  void handleChangeEffortForAllFrames(std::vector<int> indexes, double newEffort);
75  void handleUpdateFrame();
76  void handeFrameLoaded(KeyframePtr frame);
77  void disableFrame(unsigned position); // Disables specified frame if its enabled, wise wersa otherwise
78 
79  void handleTabChange(int id);
80 
81  void applyRule(double delta, int rule_id);
82 
83 private:
84  int findNextID(); // Find valid ID which is not used yet
85  int idToPosition(int id); // Find frame's position in vector by its ID
86  void setCurrentFrame(KeyframePtr frame);
87 
88  KeyframePtr createFrame();
89  KeyframePtr createFrame(KeyframePtr oldFrame, bool copyNameAndID = false);
90 
91  QVariant data(const QModelIndex &index, int role = Qt::DisplayRole) const;
92  QStringList mimeTypes() const;
93  QMimeData* mimeData(const QModelIndexList &indexes) const;
94  Qt::DropActions supportedDropActions() const;
95  Qt::ItemFlags flags(const QModelIndex &index) const;
96 
97  bool dropMimeData(const QMimeData *data, Qt::DropAction action, int row, int column, const QModelIndex &parent);
98  bool removeRows(int row, int count, const QModelIndex &parent = QModelIndex());
99  void insertRow(int row, KeyframePtr frame, const QModelIndex &parent = QModelIndex());
100 
101 private:
102  joint_perspective::PerspectiveManager *m_perspective_manager;
103 
104  motionfile::Motion m_motion;
105  KeyframePtr m_current_frame;
106 
107  // Dump of motion at a time it is being loaded. Used to define if there are some changes of motion
108  std::string m_canonic_dump;
109 
110  bool m_has_motion;
111 
112  std::vector<KeyframePtr> m_copied_frames;
113  std::vector<std::string> m_copied_joint_list;
114 };
115 
116 
117 #endif