$search

motoman::utils Namespace Reference

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.

Function Documentation

bool motoman::utils::checkJointNames ( trajectory_msgs::JointTrajectoryConstPtr  trajectory  ) 

Checks that the joint names match the assumptions made by the motoman controller interface.

Parameters:
trajectory with joint names to check
Returns:
True if joint names and order match the expected motoman order

Definition at line 57 of file utils.cpp.

bool motoman::utils::checkTrajectory ( trajectory_msgs::JointTrajectoryConstPtr  trajectory  ) 

Checks that the trajectory meets the assumptions and requirements of the motoman controller interface.

Parameters:
trajectory to check
Returns:
True if trajectory is valid and meets requirements

Definition at line 45 of file utils.cpp.

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.

Parameters:
parameter name to query (typically )
trajectory with joint names to query
joint velocity limits returned by URDQ query
Returns:
True if all velocities were found

Definition at line 125 of file utils.cpp.

bool motoman::utils::hasSuffix ( string &  str,
string &  suffix 
)

Definition at line 96 of file utils.cpp.

bool motoman::utils::hasSuffix ( std::string &  str,
std::string &  suffix 
)

Checks a string a the suffix.

Parameters:
string to check
suffix to check for
Returns:
True if str has the suffix
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.

Parameters:
joint velocity limits (order should match joint velocities)
joint velocities (order should match limits)
Returns:
Combined velocity

Definition at line 172 of file utils.cpp.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


motoman
Author(s): Shaun Edwards
autogenerated on Mon Mar 4 12:16:12 2013