NimbRo ROS Soccer Package
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Groups Pages
motionplayerclient.h
1 // Handles requests for play moton/frame, update motion, etc
2 // Author: Dmytro Pavlichenko <dm.mark999@gmail.com>
3 
4 #ifndef MOTION_PLAYER_CLIENT_H
5 #define MOTION_PLAYER_CLIENT_H
6 
7 #include <vector>
8 #include <string>
9 
10 #include <ros/ros.h>
11 #include <ros/node_handle.h>
12 #include <ros/service_client.h>
13 
14 #include <motion_file/motionfile.h>
15 
16 class MotionPlayerClient
17 {
18 public:
19  typedef boost::shared_ptr<motionfile::Keyframe> KeyframePtr;
20 
21  MotionPlayerClient();
22  ~MotionPlayerClient();
23 
24  void playMotion(motionfile::Motion motion, float duration_factor);
25  void playFrame(KeyframePtr frame, std::vector<std::string> joint_list, float duration_factor);
26  void playSequence(motionfile::Motion motion, std::vector<int> indices);
27  void updateMotion(motionfile::Motion motion);
28 
29  void tryPlayDelayedMotion(); // Plays a delayed motion if it exists
30 
31 private:
32  bool requestPlay(motionfile::Motion &motion, int type);
33  bool requestUpdate(motionfile::Motion &motion, int type);
34 
35 private:
36  bool m_has_delayed_motion;
37  motionfile::Motion m_delayed_motion; // Motion which is played after first frame was played completely
38 
39  ros::ServiceClient m_update_client;
40  ros::ServiceClient m_play_client;
41 };
42 
43 #endif