Class KinematicsInterface

Class Documentation

class KinematicsInterface

Public Functions

KinematicsInterface() = default
virtual ~KinematicsInterface() = default
virtual bool initialize(std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface> parameters_interface, const std::string &end_effector_name) = 0

Initialize plugin. This method must be called before any other.

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

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

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_jacobian(const std::vector<double> &joint_pos_vec, const std::string &link_name, Eigen::Matrix<double, 6, Eigen::Dynamic> &jacobian)