4 #ifndef MOTION_PLAYER_CLIENT_H
5 #define MOTION_PLAYER_CLIENT_H
11 #include <ros/node_handle.h>
12 #include <ros/service_client.h>
14 #include <motion_file/motionfile.h>
16 class MotionPlayerClient
19 typedef boost::shared_ptr<motionfile::Keyframe> KeyframePtr;
22 ~MotionPlayerClient();
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);
29 void tryPlayDelayedMotion();
32 bool requestPlay(motionfile::Motion &motion,
int type);
33 bool requestUpdate(motionfile::Motion &motion,
int type);
36 bool m_has_delayed_motion;
37 motionfile::Motion m_delayed_motion;
39 ros::ServiceClient m_update_client;
40 ros::ServiceClient m_play_client;