13 #include <boost/shared_ptr.hpp>
14 #include <motion_file/motionfile.h>
16 #include <ros/node_handle.h>
17 #include <ros/subscriber.h>
19 #include <robotcontrol/RobotState.h>
27 class FrameView :
public QWidget
31 typedef boost::shared_ptr<motionfile::Keyframe> KeyframePtr;
33 FrameView(QWidget *parent = 0);
36 virtual bool eventFilter(QObject *
object, QEvent *event);
38 QString getPathToDir();
41 int nameToIndex(std::string name);
43 static bool parseSupport(QString support,
double &left,
double &right);
47 void frameLoaded(KeyframePtr frame);
48 void changeEffortForAllFrames(std::vector<int> indexesToApply,
double newEffort);
54 void setFrame(KeyframePtr frame);
55 void updateJointList(
const std::vector<std::string> &jointList);
57 void setPathAndName(QString path);
61 void updateRollPitchYaw();
63 void durationSpinChanged();
64 void durationSliderChanged();
66 void enableSupport(
bool enable);
68 void supportLeftSpinChanged();
69 void supportRightSpinChanged();
70 void supportSliderChanged();
72 void handleRollSpinChanged();
73 void handlePitchSpinChanged();
74 void handleYawSpinChanged();
77 void setAllChecked(
bool flag);
80 void findIndices(std::vector<int> &indices);
81 void setCurrentSupport();
82 void setSupportFromFrame();
84 void robotStateReceived(
const robotcontrol::RobotStateConstPtr& state);
90 std::vector<std::string> joints;
96 ros::Subscriber subscriber;
100 #endif // FRAMEVIEW_H