Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00040 #ifndef PLAYMOTIONHELPERS_H
00041 #define PLAYMOTIONHELPERS_H
00042
00043 #include <string>
00044 #include "play_motion/datatypes.h"
00045
00046 namespace ros
00047 {
00048 class NodeHandle;
00049 }
00050
00051 namespace play_motion
00052 {
00053
00054 struct MotionInfo
00055 {
00056 std::string id;
00057 std::string name;
00058 std::string usage;
00059 std::string description;
00060 JointNames joints;
00061 Trajectory traj;
00062 };
00063
00069 void getMotionJoints(const ros::NodeHandle &nh, const std::string& motion_id,
00070 JointNames& motion_joints);
00071 void getMotionJoints(const std::string& motion_id, JointNames& motion_joints);
00072
00073
00079 void getMotionPoints(const ros::NodeHandle &nh, const std::string& motion_id,
00080 Trajectory& motion_points);
00081 void getMotionPoints(const std::string& motion_id, Trajectory& motion_points);
00082
00083
00088 ros::Duration getMotionDuration(const ros::NodeHandle &nh,
00089 const std::string &motion_id);
00090
00097 void getMotionIds(const ros::NodeHandle &nh, MotionNames& motion_ids);
00098 void getMotionIds(MotionNames& motion_ids);
00099
00106 bool motionExists(const ros::NodeHandle &nh, const std::string &motion_id);
00107 bool motionExists(const std::string &motion_id);
00108
00115 bool isAlreadyThere(const JointNames &target_joints, const TrajPoint &target_point,
00116 const JointNames &source_joints, const TrajPoint &source_point,
00117 double tolerance = 0.15);
00118
00142 void populateVelocities(const TrajPoint& point_prev,
00143 const TrajPoint& point_next,
00144 TrajPoint& point_curr);
00145
00159 void populateVelocities(const Trajectory& traj_in, Trajectory& traj_out);
00160
00169 void getMotion(const ros::NodeHandle &nh, const std::string &motion_id,
00170 MotionInfo &motion_info);
00171 void getMotion(const std::string &motion_id, MotionInfo &motion_info);
00172 }
00173
00174 #endif