Go to the source code of this file.
Classes | |
struct | play_motion::MotionInfo |
Namespaces | |
namespace | play_motion |
namespace | ros |
Functions | |
void | play_motion::getMotion (const ros::NodeHandle &nh, const std::string &motion_id, MotionInfo &motion_info) |
Parse a motion specified in the ROS parameter server into a data structure. | |
void | play_motion::getMotion (const std::string &motion_id, MotionInfo &motion_info) |
ros::Duration | play_motion::getMotionDuration (const ros::NodeHandle &nh, const std::string &motion_id) |
getMotionDuration gets the total duration of a motion | |
void | play_motion::getMotionIds (const ros::NodeHandle &nh, MotionNames &motion_ids) |
getMotions obtain all motion names | |
void | play_motion::getMotionIds (MotionNames &motion_ids) |
void | play_motion::getMotionJoints (const ros::NodeHandle &nh, const std::string &motion_id, JointNames &motion_joints) |
void | play_motion::getMotionJoints (const std::string &motion_id, JointNames &motion_joints) |
void | play_motion::getMotionPoints (const ros::NodeHandle &nh, const std::string &motion_id, Trajectory &motion_points) |
void | play_motion::getMotionPoints (const std::string &motion_id, Trajectory &motion_points) |
bool | play_motion::isAlreadyThere (const JointNames &target_joints, const TrajPoint &target_point, const JointNames &source_joints, const TrajPoint &source_point, double tolerance=0.15) |
isAlreadyThere checks if the source trajPoint matches the target trajPoint with a certain tolerance only the joints in targetJoint will be checked | |
bool | play_motion::motionExists (const ros::NodeHandle &nh, const std::string &motion_id) |
bool | play_motion::motionExists (const std::string &motion_id) |
void | play_motion::populateVelocities (const TrajPoint &point_prev, const TrajPoint &point_next, TrajPoint &point_curr) |
Populate joint velocity information of a trajectory waypoint. | |
void | play_motion::populateVelocities (const Trajectory &traj_in, Trajectory &traj_out) |
Populate joint velocity information of a trajectory. |