Namespaces | |
namespace | move_joint |
Classes | |
class | ApproachPlanner |
TODO. More... | |
class | ControllerUpdater |
struct | MotionInfo |
class | MoveJointGroup |
class | PlayMotion |
class | PlayMotionServer |
class | PMException |
Typedefs | |
typedef std::vector< std::string > | JointNames |
typedef std::vector< std::string > | MotionNames |
typedef play_motion_msgs::PlayMotionResult | PMR |
typedef std::vector< TrajPoint > | Trajectory |
typedef trajectory_msgs::JointTrajectoryPoint | TrajPoint |
Functions | |
void | extractJoints (xh::Array &joint_names, JointNames &motion_joints) |
void | extractTrajectory (xh::Array &traj_points, Trajectory &motion_points) |
void | 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 | getMotion (const std::string &motion_id, MotionInfo &motion_info) |
ros::Duration | getMotionDuration (const ros::NodeHandle &nh, const std::string &motion_id) |
getMotionDuration gets the total duration of a motion | |
ros::Duration | getMotionDuration (const std::string &motion_id) |
void | getMotionIds (const ros::NodeHandle &nh, MotionNames &motion_ids) |
getMotions obtain all motion names | |
void | getMotionIds (MotionNames &motion_ids) |
void | getMotionJoints (const ros::NodeHandle &nh, const std::string &motion_id, JointNames &motion_joints) |
void | getMotionJoints (const std::string &motion_id, JointNames &motion_joints) |
void | getMotionPoints (const ros::NodeHandle &nh, const std::string &motion_id, Trajectory &motion_points) |
void | getMotionPoints (const std::string &motion_id, Trajectory &motion_points) |
ros::NodeHandle | getMotionsNodeHandle (const ros::NodeHandle &nh) |
static ros::ServiceClient | initCmClient (ros::NodeHandle nh) |
bool | 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 | |
static bool | isJointTrajectoryController (const std::string &name) |
bool | motionExists (const ros::NodeHandle &nh, const std::string &motion_id) |
bool | motionExists (const std::string &motion_id) |
void | populateVelocities (const TrajPoint &point_prev, const TrajPoint &point_next, TrajPoint &point_curr) |
Populate joint velocity information of a trajectory waypoint. | |
void | populateVelocities (const Trajectory &traj_in, Trajectory &traj_out) |
Populate joint velocity information of a trajectory. |
typedef std::vector<std::string> play_motion::JointNames |
Definition at line 48 of file datatypes.h.
typedef std::vector<std::string> play_motion::MotionNames |
Definition at line 47 of file datatypes.h.
typedef play_motion_msgs::PlayMotionResult play_motion::PMR |
Definition at line 56 of file play_motion.h.
typedef std::vector<TrajPoint> play_motion::Trajectory |
Definition at line 50 of file datatypes.h.
typedef trajectory_msgs::JointTrajectoryPoint play_motion::TrajPoint |
Definition at line 49 of file datatypes.h.
void play_motion::extractJoints | ( | xh::Array & | joint_names, |
JointNames & | motion_joints | ||
) |
Definition at line 84 of file play_motion_helpers.cpp.
void play_motion::extractTrajectory | ( | xh::Array & | traj_points, |
Trajectory & | motion_points | ||
) |
Definition at line 53 of file play_motion_helpers.cpp.
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.
[in] | nh | Nodehandle with the namespace containing the motions (When omitted, defaults to ros::NodeHandle nh("play_motion")) |
[in] | motion_id | Motion identifier |
[out] | motionInfo | Data structure containing parsed motion |
ros::Exception | if the motion does not exist or is malformed. |
Definition at line 255 of file play_motion_helpers.cpp.
void play_motion::getMotion | ( | const std::string & | motion_id, |
MotionInfo & | motion_info | ||
) |
Definition at line 284 of file play_motion_helpers.cpp.
ros::Duration play_motion::getMotionDuration | ( | const ros::NodeHandle & | nh, |
const std::string & | motion_id | ||
) |
getMotionDuration gets the total duration of a motion
xh::XmlrpcHelperException | if motion_id cannot be found |
Definition at line 196 of file play_motion_helpers.cpp.
ros::Duration play_motion::getMotionDuration | ( | const std::string & | motion_id | ) |
Definition at line 204 of file play_motion_helpers.cpp.
void play_motion::getMotionIds | ( | const ros::NodeHandle & | nh, |
MotionNames & | motion_ids | ||
) |
getMotions obtain all motion names
nh | Nodehandle with the namespace containing the motions (When omitted, defaults to ros::NodeHandle nh("play_motion")) |
xh::XmlrpcHelperException | if no motions available |
Definition at line 120 of file play_motion_helpers.cpp.
void play_motion::getMotionIds | ( | MotionNames & | motion_ids | ) |
Definition at line 131 of file play_motion_helpers.cpp.
void play_motion::getMotionJoints | ( | const ros::NodeHandle & | nh, |
const std::string & | motion_id, | ||
JointNames & | motion_joints | ||
) |
nh | Nodehandle with the namespace containing the motions (When omitted, defaults to ros::NodeHandle nh("play_motion")) |
xh::XmlrpcHelperException | if motion_id cannot be found |
Definition at line 92 of file play_motion_helpers.cpp.
void play_motion::getMotionJoints | ( | const std::string & | motion_id, |
JointNames & | motion_joints | ||
) |
Definition at line 100 of file play_motion_helpers.cpp.
void play_motion::getMotionPoints | ( | const ros::NodeHandle & | nh, |
const std::string & | motion_id, | ||
Trajectory & | motion_points | ||
) |
nh | Nodehandle with the namespace containing the motions (When omitted, defaults to ros::NodeHandle nh("play_motion")) |
xh::XmlrpcHelperException | if motion_id cannot be found |
Definition at line 106 of file play_motion_helpers.cpp.
void play_motion::getMotionPoints | ( | const std::string & | motion_id, |
Trajectory & | motion_points | ||
) |
Definition at line 114 of file play_motion_helpers.cpp.
ros::NodeHandle play_motion::getMotionsNodeHandle | ( | const ros::NodeHandle & | nh | ) |
Definition at line 48 of file play_motion_helpers.cpp.
static ros::ServiceClient play_motion::initCmClient | ( | ros::NodeHandle | nh | ) | [static] |
Definition at line 47 of file controller_updater.cpp.
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
tolerance | tolerance per joint in radians |
If a joint used in the target is not used in the available in the source can't guarantee that the points are equivalent
If a joint used in the target is not used in the available in the source can't guarantee that the points are equivalent
Definition at line 229 of file play_motion_helpers.cpp.
static bool play_motion::isJointTrajectoryController | ( | const std::string & | name | ) | [static] |
Definition at line 62 of file controller_updater.cpp.
bool play_motion::motionExists | ( | const ros::NodeHandle & | nh, |
const std::string & | motion_id | ||
) |
nh | Nodehandle with the namespace containing the motions (When omitted, defaults to ros::NodeHandle nh("play_motion")) |
motion_id | Motion identifier |
Definition at line 210 of file play_motion_helpers.cpp.
bool play_motion::motionExists | ( | const std::string & | motion_id | ) |
Definition at line 223 of file play_motion_helpers.cpp.
void play_motion::populateVelocities | ( | const TrajPoint & | point_prev, |
const TrajPoint & | point_next, | ||
TrajPoint & | point_curr | ||
) |
Populate joint velocity information of a trajectory waypoint.
Joint velocities are computed by numeric differentiation of position information, except in the following cases, where it is set to zero:
where , and are the positions of a joint at the previous, current and next waypoint. This heuristic is well suited for direction reversals and position holding without overshoot, and produces better results than pure numeric differentiation.
If the input waypoint already contains a valid velocity specification, it will not be overwritten, that is, this method will be a no-op.
[in] | point_prev | Previous trajectory waypoint. |
[in] | point_next | Next trajectory waypoint. |
[out] | point_curr | Trajectory waypoint to which velocity information will be added. |
Definition at line 137 of file play_motion_helpers.cpp.
void play_motion::populateVelocities | ( | const Trajectory & | traj_in, |
Trajectory & | traj_out | ||
) |
Populate joint velocity information of a trajectory.
Joint velocities will be computed for all waypoints not containing a valid velocity specification. Waypoints with an existing velocity specification will not be modified. If the trajectory endpoints don't specify velocites, they will be set to zero.
[in] | traj_in | Input trajectory. Some waypoints may have a velocity specification (or not at all). |
[out] | traj_out | Output trajectory. All waypoints have a velocity specification. Can be the same instance as traj_in . |
Definition at line 178 of file play_motion_helpers.cpp.