Skip to content

Commit

Permalink
Add the KDL implementation for the computation of the jacobian inverse
Browse files Browse the repository at this point in the history
  • Loading branch information
francescodonofrio committed Nov 14, 2024
1 parent 652ec2c commit 753504a
Show file tree
Hide file tree
Showing 2 changed files with 44 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -60,12 +60,17 @@ class KinematicsInterfaceKDL : public kinematics_interface::KinematicsInterface
const Eigen::VectorXd & joint_pos, const std::string & link_name,
Eigen::Matrix<double, 6, Eigen::Dynamic> & jacobian) override;

bool calculate_jacobian_inverse(
const Eigen::VectorXd & joint_pos, const std::string & link_name,
Eigen::Matrix<double, Eigen::Dynamic, 6> & jacobian_inverse) override;

private:
// verification methods
bool verify_initialized();
bool verify_link_name(const std::string & link_name);
bool verify_joint_vector(const Eigen::VectorXd & joint_vector);
bool verify_jacobian(const Eigen::Matrix<double, 6, Eigen::Dynamic> & jacobian);
bool verify_jacobian_inverse(const Eigen::Matrix<double, Eigen::Dynamic, 6> & jacobian);

bool initialized = false;
std::string root_name_;
Expand Down
39 changes: 39 additions & 0 deletions kinematics_interface_kdl/src/kinematics_interface_kdl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -182,6 +182,31 @@ bool KinematicsInterfaceKDL::calculate_jacobian(
return true;
}

bool KinematicsInterfaceKDL::calculate_jacobian_inverse(
const Eigen::VectorXd & joint_pos, const std::string & link_name,
Eigen::Matrix<double, Eigen::Dynamic, 6> & jacobian_inverse)
{
// verify inputs
if (
!verify_initialized() || !verify_joint_vector(joint_pos) || !verify_link_name(link_name) ||
!verify_jacobian_inverse(jacobian_inverse))
{
return false;
}

// get joint array
q_.data = joint_pos;

// calculate Jacobian
jac_solver_->JntToJac(q_, *jacobian_, link_name_map_[link_name]);
Eigen::Matrix<double, 6, Eigen::Dynamic> jacobian = jacobian_->data;

// damped inverse
jacobian_inverse = (jacobian.transpose() * jacobian + alpha * I).inverse() * jacobian.transpose();

return true;
}

bool KinematicsInterfaceKDL::calculate_link_transform(
const Eigen::Matrix<double, Eigen::Dynamic, 1> & joint_pos, const std::string & link_name,
Eigen::Isometry3d & transform)
Expand Down Expand Up @@ -269,6 +294,20 @@ bool KinematicsInterfaceKDL::verify_jacobian(
return true;
}

bool KinematicsInterfaceKDL::verify_jacobian_inverse(
const Eigen::Matrix<double, Eigen::Dynamic, 6> & jacobian_inverse)
{
if (
jacobian_inverse.rows() != jacobian_->columns() || jacobian_inverse.cols() != jacobian_->rows())
{
RCLCPP_ERROR(
LOGGER, "The size of the jacobian (%zu, %zu) does not match the required size of (%u, %u)",
jacobian_inverse.rows(), jacobian_inverse.cols(), jacobian_->columns(), jacobian_->rows());
return false;
}
return true;
}

} // namespace kinematics_interface_kdl

#include "pluginlib/class_list_macros.hpp"
Expand Down

0 comments on commit 753504a

Please sign in to comment.