$search
Functions | |
bool | checkJointNames (trajectory_msgs::JointTrajectoryConstPtr trajectory) |
Checks that the joint names match the assumptions made by the motoman controller interface. | |
bool | checkTrajectory (trajectory_msgs::JointTrajectoryConstPtr trajectory) |
Checks that the trajectory meets the assumptions and requirements of the motoman controller interface. | |
bool | getVelocityLimits (std::string param_name, trajectory_msgs::JointTrajectoryConstPtr trajectory, std::vector< double > &joint_velocity_limits) |
Queries the URDF parameter server to determine what the velocity limits are for the joint names that are pased in. The order of the velocity limits returned (by reference) matches the joint name order. NOTE: This process is an expensive one. The results of this call should be cached for future needs. | |
bool | hasSuffix (string &str, string &suffix) |
bool | hasSuffix (std::string &str, std::string &suffix) |
Checks a string a the suffix. | |
double | toMotomanVelocity (std::vector< double > &joint_velocity_limits, std::vector< double > &joint_velocities) |
Converts the ROS trajectory velocity (individual joint velocities to the combined motoman velocity which is highest joint velocity required as a fraction of the joint velocity limit. |
bool motoman::utils::checkJointNames | ( | trajectory_msgs::JointTrajectoryConstPtr | trajectory | ) |
bool motoman::utils::checkTrajectory | ( | trajectory_msgs::JointTrajectoryConstPtr | trajectory | ) |
bool motoman::utils::getVelocityLimits | ( | std::string | param_name, | |
trajectory_msgs::JointTrajectoryConstPtr | trajectory, | |||
std::vector< double > & | joint_velocity_limits | |||
) |
Queries the URDF parameter server to determine what the velocity limits are for the joint names that are pased in. The order of the velocity limits returned (by reference) matches the joint name order. NOTE: This process is an expensive one. The results of this call should be cached for future needs.
parameter | name to query (typically ) | |
trajectory | with joint names to query | |
joint | velocity limits returned by URDQ query |
bool motoman::utils::hasSuffix | ( | string & | str, | |
string & | suffix | |||
) |
bool motoman::utils::hasSuffix | ( | std::string & | str, | |
std::string & | suffix | |||
) |
Checks a string a the suffix.
string | to check | |
suffix | to check for |
double motoman::utils::toMotomanVelocity | ( | std::vector< double > & | joint_velocity_limits, | |
std::vector< double > & | joint_velocities | |||
) |
Converts the ROS trajectory velocity (individual joint velocities to the combined motoman velocity which is highest joint velocity required as a fraction of the joint velocity limit.
joint | velocity limits (order should match joint velocities) | |
joint | velocities (order should match limits) |