Class KinematicsInterface
- Defined in File kinematics_interface.hpp 
Class Documentation
- 
class KinematicsInterface
- Public Functions - 
KinematicsInterface() = default
 - 
virtual ~KinematicsInterface() = default
 - Initialize plugin. This method must be called before any other. - Parameters:
- robot_description – [in] robot URDF in string format 
- parameters_interface – [in] 
- param_namespace – [in] namespace for kinematics parameters - defaults to “kinematics” 
 
- Returns:
- true if successful 
 
 - 
virtual bool convert_cartesian_deltas_to_joint_deltas(const Eigen::VectorXd &joint_pos, const Eigen::Matrix<double, 6, 1> &delta_x, const std::string &link_name, Eigen::VectorXd &delta_theta) = 0
- Convert Cartesian delta-x to joint delta-theta, using the Jacobian. - Parameters:
- joint_pos – [in] joint positions of the robot in radians 
- delta_x – [in] input Cartesian deltas (x, y, z, wx, wy, wz) 
- link_name – [in] the link name at which delta_x is applied 
- delta_theta – [out] outputs joint deltas 
 
- Returns:
- true if successful 
 
 - 
virtual bool convert_joint_deltas_to_cartesian_deltas(const Eigen::VectorXd &joint_pos, const Eigen::VectorXd &delta_theta, const std::string &link_name, Eigen::Matrix<double, 6, 1> &delta_x) = 0
- Convert joint delta-theta to Cartesian delta-x. - Parameters:
- joint_pos – joint positions of the robot in radians 
- delta_theta – [in] joint deltas 
- link_name – [in] the link name at which delta_x is calculated 
- delta_x – [out] Cartesian deltas (x, y, z, wx, wy, wz) 
 
- Returns:
- true if successful 
 
 - 
virtual bool calculate_link_transform(const Eigen::VectorXd &joint_pos, const std::string &link_name, Eigen::Isometry3d &transform) = 0
- Calculates the joint transform for a specified link using provided joint positions. - Parameters:
- joint_pos – [in] joint positions of the robot in radians 
- link_name – [in] the name of the link to find the transform for 
- transform – [out] transformation matrix of the specified link 
 
- Returns:
- true if successful 
 
 - 
virtual bool calculate_jacobian(const Eigen::VectorXd &joint_pos, const std::string &link_name, Eigen::Matrix<double, 6, Eigen::Dynamic> &jacobian) = 0
- Calculates the jacobian for a specified link using provided joint positions. - Parameters:
- joint_pos – [in] joint positions of the robot in radians 
- link_name – [in] the name of the link to find the transform for 
- jacobian – [out] Jacobian matrix of the specified link in column major format. 
 
- Returns:
- true if successful 
 
 - 
virtual bool calculate_jacobian_inverse(const Eigen::VectorXd &joint_pos, const std::string &link_name, Eigen::Matrix<double, Eigen::Dynamic, 6> &jacobian_inverse) = 0
- Calculates the jacobian inverse for a specified link using provided joint positions. - Parameters:
- joint_pos – [in] joint positions of the robot in radians 
- link_name – [in] the name of the link to find the transform for 
- jacobian_inverse – [out] Jacobian inverse matrix of the specified link in row major format. 
 
- Returns:
- true if successful 
 
 - 
virtual bool calculate_frame_difference(Eigen::Matrix<double, 7, 1> &x_a, Eigen::Matrix<double, 7, 1> &x_b, double dt, Eigen::Matrix<double, 6, 1> &delta_x) = 0
- Calculates the difference between two Cartesian frames. - Parameters:
- x_a – [in] first Cartesian frame (x, y, z, wx, wy, wz, ww) 
- x_b – [in] second Cartesian frame (x, y, z, wx, wy, wz, ww) 
- dt – [in] time interval over which the numerical differentiation takes place 
- delta_x – [out] Cartesian deltas (x, y, z, wx, wy, wz) 
 
- Returns:
- true if successful 
 
 - 
bool convert_cartesian_deltas_to_joint_deltas(std::vector<double> &joint_pos_vec, const std::vector<double> &delta_x_vec, const std::string &link_name, std::vector<double> &delta_theta_vec)
 - 
bool convert_joint_deltas_to_cartesian_deltas(const std::vector<double> &joint_pos_vec, const std::vector<double> &delta_theta_vec, const std::string &link_name, std::vector<double> &delta_x_vec)
 - 
bool calculate_link_transform(const std::vector<double> &joint_pos_vec, const std::string &link_name, Eigen::Isometry3d &transform)
 - 
bool calculate_jacobian(const std::vector<double> &joint_pos_vec, const std::string &link_name, Eigen::Matrix<double, 6, Eigen::Dynamic> &jacobian)
 - 
bool calculate_jacobian_inverse(const std::vector<double> &joint_pos_vec, const std::string &link_name, Eigen::Matrix<double, Eigen::Dynamic, 6> &jacobian_inverse)
 - 
bool calculate_frame_difference(std::vector<double> &x_a_vec, std::vector<double> &x_b_vec, double dt, std::vector<double> &delta_x_vec)
 
- 
KinematicsInterface() = default