Classes | |
class | HandKinematicsPlugin |
Functions | |
bool | checkFKService (moveit_msgs::GetPositionFK::Request &request, moveit_msgs::GetPositionFK::Response &response, const moveit_msgs::KinematicSolverInfo &chain_info) |
bool | checkIKService (moveit_msgs::GetPositionIK::Request &request, moveit_msgs::GetPositionIK::Response &response, const moveit_msgs::KinematicSolverInfo &chain_info) |
bool | checkJointNames (const std::vector< std::string > &joint_names, const moveit_msgs::KinematicSolverInfo &chain_info) |
bool | checkLinkName (const std::string &link_name, const moveit_msgs::KinematicSolverInfo &chain_info) |
bool | checkLinkNames (const std::vector< std::string > &link_names, const moveit_msgs::KinematicSolverInfo &chain_info) |
bool | checkRobotState (moveit_msgs::RobotState &robot_state, const moveit_msgs::KinematicSolverInfo &chain_info) |
bool | convertPoseToRootFrame (const geometry_msgs::PoseStamped &pose_msg, KDL::Frame &pose_kdl, const std::string &root_frame, tf::TransformListener &tf) |
bool | convertPoseToRootFrame (const geometry_msgs::PoseStamped &pose_msg, geometry_msgs::PoseStamped &pose_msg_out, const std::string &root_frame, tf::TransformListener &tf) |
int | getJointIndex (const std::string &name, const moveit_msgs::KinematicSolverInfo &chain_info) |
bool | getKDLChain (const std::string &xml_string, const std::string &root_name, const std::string &tip_name, KDL::Chain &kdl_chain) |
void | getKDLChainInfo (const KDL::Chain &chain, moveit_msgs::KinematicSolverInfo &chain_info) |
int | getKDLSegmentIndex (const KDL::Chain &chain, const std::string &name) |
bool | getKDLTree (const std::string &xml_string, const std::string &root_name, const std::string &tip_name, KDL::Tree &kdl_chain) |
bool | init_ik (urdf::Model &robot_model, const std::string &root_name, const std::string &tip_name, KDL::JntArray &joint_min, KDL::JntArray &joint_max, moveit_msgs::KinematicSolverInfo &info) |
bool | loadRobotModel (ros::NodeHandle node_handle, urdf::Model &robot_model, std::string &root_name, std::string &tip_name, std::string &xml_string) |
Eigen::MatrixXd | updateCouplingFF (const KDL::JntArray &q) |
Eigen::MatrixXd | updateCouplingLF (const KDL::JntArray &q) |
Eigen::MatrixXd | updateCouplingMF (const KDL::JntArray &q) |
Eigen::MatrixXd | updateCouplingRF (const KDL::JntArray &q) |
Eigen::MatrixXd | updateCouplingTH (const KDL::JntArray &q) |
Variables | |
static const double | IK_DEFAULT_TIMEOUT = 10.0 |
static const double | IK_DEFAULT_TIMEOUT = 10.0 |
bool hand_kinematics::checkFKService | ( | moveit_msgs::GetPositionFK::Request & | request, |
moveit_msgs::GetPositionFK::Response & | response, | ||
const moveit_msgs::KinematicSolverInfo & | chain_info | ||
) |
Definition at line 225 of file hand_kinematics_utils.cpp.
bool hand_kinematics::checkIKService | ( | moveit_msgs::GetPositionIK::Request & | request, |
moveit_msgs::GetPositionIK::Response & | response, | ||
const moveit_msgs::KinematicSolverInfo & | chain_info | ||
) |
Definition at line 243 of file hand_kinematics_utils.cpp.
bool hand_kinematics::checkJointNames | ( | const std::vector< std::string > & | joint_names, |
const moveit_msgs::KinematicSolverInfo & | chain_info | ||
) |
Definition at line 154 of file hand_kinematics_utils.cpp.
bool hand_kinematics::checkLinkName | ( | const std::string & | link_name, |
const moveit_msgs::KinematicSolverInfo & | chain_info | ||
) |
Definition at line 194 of file hand_kinematics_utils.cpp.
bool hand_kinematics::checkLinkNames | ( | const std::vector< std::string > & | link_names, |
const moveit_msgs::KinematicSolverInfo & | chain_info | ||
) |
Definition at line 177 of file hand_kinematics_utils.cpp.
bool hand_kinematics::checkRobotState | ( | moveit_msgs::RobotState & | robot_state, |
const moveit_msgs::KinematicSolverInfo & | chain_info | ||
) |
Definition at line 207 of file hand_kinematics_utils.cpp.
bool hand_kinematics::convertPoseToRootFrame | ( | const geometry_msgs::PoseStamped & | pose_msg, |
KDL::Frame & | pose_kdl, | ||
const std::string & | root_frame, | ||
tf::TransformListener & | tf | ||
) |
Definition at line 278 of file hand_kinematics_utils.cpp.
bool hand_kinematics::convertPoseToRootFrame | ( | const geometry_msgs::PoseStamped & | pose_msg, |
geometry_msgs::PoseStamped & | pose_msg_out, | ||
const std::string & | root_frame, | ||
tf::TransformListener & | tf | ||
) |
Definition at line 293 of file hand_kinematics_utils.cpp.
int hand_kinematics::getJointIndex | ( | const std::string & | name, |
const moveit_msgs::KinematicSolverInfo & | chain_info | ||
) |
Definition at line 266 of file hand_kinematics_utils.cpp.
bool hand_kinematics::getKDLChain | ( | const std::string & | xml_string, |
const std::string & | root_name, | ||
const std::string & | tip_name, | ||
KDL::Chain & | kdl_chain | ||
) |
Definition at line 96 of file hand_kinematics_utils.cpp.
void hand_kinematics::getKDLChainInfo | ( | const KDL::Chain & | chain, |
moveit_msgs::KinematicSolverInfo & | chain_info | ||
) |
Definition at line 127 of file hand_kinematics_utils.cpp.
int hand_kinematics::getKDLSegmentIndex | ( | const KDL::Chain & | chain, |
const std::string & | name | ||
) |
Definition at line 138 of file hand_kinematics_utils.cpp.
bool hand_kinematics::getKDLTree | ( | const std::string & | xml_string, |
const std::string & | root_name, | ||
const std::string & | tip_name, | ||
KDL::Tree & | kdl_chain | ||
) |
Definition at line 114 of file hand_kinematics_utils.cpp.
bool hand_kinematics::init_ik | ( | urdf::Model & | robot_model, |
const std::string & | root_name, | ||
const std::string & | tip_name, | ||
KDL::JntArray & | joint_min, | ||
KDL::JntArray & | joint_max, | ||
moveit_msgs::KinematicSolverInfo & | info | ||
) |
Definition at line 418 of file hand_kinematics_utils.cpp.
bool hand_kinematics::loadRobotModel | ( | ros::NodeHandle | node_handle, |
urdf::Model & | robot_model, | ||
std::string & | root_name, | ||
std::string & | tip_name, | ||
std::string & | xml_string | ||
) |
Definition at line 46 of file hand_kinematics_utils.cpp.
Eigen::MatrixXd hand_kinematics::updateCouplingFF | ( | const KDL::JntArray & | q | ) |
Definition at line 335 of file hand_kinematics_utils.cpp.
Eigen::MatrixXd hand_kinematics::updateCouplingLF | ( | const KDL::JntArray & | q | ) |
Definition at line 392 of file hand_kinematics_utils.cpp.
Eigen::MatrixXd hand_kinematics::updateCouplingMF | ( | const KDL::JntArray & | q | ) |
Definition at line 354 of file hand_kinematics_utils.cpp.
Eigen::MatrixXd hand_kinematics::updateCouplingRF | ( | const KDL::JntArray & | q | ) |
Definition at line 373 of file hand_kinematics_utils.cpp.
Eigen::MatrixXd hand_kinematics::updateCouplingTH | ( | const KDL::JntArray & | q | ) |
Definition at line 412 of file hand_kinematics_utils.cpp.
|
static |
Definition at line 44 of file hand_kinematics_utils.cpp.
|
static |
Definition at line 74 of file hand_kinematics_coupling_plugin.cpp.