1414//
1515// / \author: Andy Zelenak
1616
17- #include " admittance_controller/incremental_ik_calculator .hpp"
17+ #include " admittance_controller/incremental_kinematics .hpp"
1818
19- #include " Eigen/VectorXf "
19+ #include " Eigen/VectorXd "
2020#include " tf2_eigen/tf2_eigen.h"
2121
2222namespace admittance_controller
2323{
24- IncrementalIKCalculator::IncrementalIKCalculator (const std::shared_ptr<rclcpp::Node> & node, const std::string & group_name) : node_(node)
24+ IncrementalKinematics::IncrementalKinematics (const std::shared_ptr<rclcpp::Node> & node, const std::string & group_name) : node_(node)
2525{
2626 // TODO(andyz): Parameterize robot description and joint group
2727 std::unique_ptr<robot_model_loader::RobotModelLoader> model_loader_ptr =
@@ -34,23 +34,25 @@ IncrementalIKCalculator::IncrementalIKCalculator(const std::shared_ptr<rclcpp::N
3434 // By default, the MoveIt Jacobian frame is the last link
3535}
3636
37- bool IncrementalIKCalculator ::convertCartesianDeltasToJointDeltas (const std::vector<double > & delta_x_vec, const geometry_msgs::msg::TransformStamped & ik_base_to_tip_trafo , std::vector<double > & delta_theta_vec)
37+ bool IncrementalKinematics ::convertCartesianDeltasToJointDeltas (const std::vector<double > & delta_x_vec, const geometry_msgs::msg::TransformStamped & ik_base_to_tip_tf , std::vector<double > & delta_theta_vec)
3838{
3939 // see here for this conversion: https://stackoverflow.com/questions/26094379/typecasting-eigenvectorxd-to-stdvector
40- Eigen::VectorXf delta_x = Eigen::Map<Eigen::VectorXf , Eigen::Unaligned>(&delta_x_vec[0 ], delta_x_vec.size ());
40+ Eigen::VectorXd delta_x = Eigen::Map<Eigen::VectorXd , Eigen::Unaligned>(&delta_x_vec[0 ], delta_x_vec.size ());
4141
4242 // Transform delta_x to the moveit_jacobian_frame
43+ // TODO: replace when this PR to tf2_eigen is merged
44+ // https://github.com/ros2/geometry2/pull/406
4345 try
4446 {
4547 // 4x4 transformation matrix
46- const Eigen::Isometry3d affine_transform = tf2::transformToEigen (ik_base_to_tip_trafo );
48+ const Eigen::Isometry3d affine_transform = tf2::transformToEigen (ik_base_to_tip_tf );
4749
4850 // Build the 6x6 transformation matrix
4951 Eigen::MatrixXd twist_transform (6 ,6 );
5052 // upper left 3x3 block is the rotation part
5153 twist_transform.block (0 ,0 ,3 ,3 ) = affine_transform.rotation ();
5254 // upper right 3x3 block is all zeros
53- twist_transform.block (0 ,4 ,3 ,3 ) = Eigen::MatrixXd::Zero (3 ,3 );
55+ twist_transform.block (0 ,3 ,3 ,3 ) = Eigen::MatrixXd::Zero (3 ,3 );
5456 // lower left 3x3 block is tricky. See https://core.ac.uk/download/pdf/154240607.pdf
5557 Eigen::MatrixXd pos_vector_3x3 (3 ,3 );
5658 pos_vector_3x3 (0 ,0 ) = 0 ; pos_vector_3x3 (0 ,1 ) = -affine_transform.translation ().z (); pos_vector_3x3 (0 ,2 ) = affine_transform.translation ().y ();
@@ -73,17 +75,59 @@ bool IncrementalIKCalculator::convertCartesianDeltasToJointDeltas(const std::vec
7375 svd_ = Eigen::JacobiSVD<Eigen::MatrixXd>(jacobian_, Eigen::ComputeThinU | Eigen::ComputeThinV);
7476 matrix_s_ = svd_.singularValues ().asDiagonal ();
7577 pseudo_inverse_ = svd_.matrixV () * matrix_s_.inverse () * svd_.matrixU ().transpose ();
76- Eigen::VectorXf delta_theta = pseudo_inverse_ * delta_x;
78+ Eigen::VectorXd delta_theta = pseudo_inverse_ * delta_x;
7779
7880 std::vector<double > delta_theta_v (&delta_theta[0 ], delta_theta.data () + delta_theta.cols () * delta_theta.rows ());
7981 delta_theta_vec = delta_theta_v;
8082
8183 return true ;
8284}
8385
84- bool IncrementalIKCalculator ::convertJointDeltasToCartesianDeltas (const std::vector<double > & delta_theta_vec, const geometry_msgs::msg::TransformStamped & ik_base_to_tip_trafo , std::vector<double > & delta_x_vec)
86+ bool IncrementalKinematics ::convertJointDeltasToCartesianDeltas (const std::vector<double > & delta_theta_vec, const geometry_msgs::msg::TransformStamped & ik_base_to_tip_tf , std::vector<double > & delta_x_vec)
8587{
86- // TODO(andyz): Please add here FK implementation
88+ // see here for this conversion: https://stackoverflow.com/questions/26094379/typecasting-eigenvectorxd-to-stdvector
89+ Eigen::VectorXd delta_theta = Eigen::Map<Eigen::VectorXd, Eigen::Unaligned>(&delta_theta_vec[0 ], delta_theta_vec.size ());
90+
91+ // Multiply with the Jacobian to get delta_x
92+ jacobian_ = kinematic_state_->getJacobian (joint_model_group_);
93+ // delta_x will be in the working frame of MoveIt
94+ Eigen::VectorXd delta_x = jacobian_ * delta_theta;
95+
96+ // Transform delta_x to the tip frame
97+ // TODO: replace when this PR to tf2_eigen is merged
98+ // https://github.com/ros2/geometry2/pull/406
99+ try
100+ {
101+ // 4x4 transformation matrix
102+ const Eigen::Isometry3d affine_transform = tf2::transformToEigen (ik_base_to_tip_tf);
103+
104+ // Build the 6x6 transformation matrix
105+ Eigen::MatrixXd twist_transform (6 ,6 );
106+ // upper left 3x3 block is the rotation part
107+ twist_transform.block (0 ,0 ,3 ,3 ) = affine_transform.rotation ();
108+ // upper right 3x3 block is all zeros
109+ twist_transform.block (0 ,3 ,3 ,3 ) = Eigen::MatrixXd::Zero (3 ,3 );
110+ // lower left 3x3 block is tricky. See https://core.ac.uk/download/pdf/154240607.pdf
111+ Eigen::MatrixXd pos_vector_3x3 (3 ,3 );
112+ pos_vector_3x3 (0 ,0 ) = 0 ; pos_vector_3x3 (0 ,1 ) = -affine_transform.translation ().z (); pos_vector_3x3 (0 ,2 ) = affine_transform.translation ().y ();
113+ pos_vector_3x3 (1 , 0 ) = affine_transform.translation ().z (); pos_vector_3x3 (1 ,1 ) = 0 ; pos_vector_3x3 (1 ,2 ) = -affine_transform.translation ().x ();
114+ pos_vector_3x3 (2 , 0 ) = -affine_transform.translation ().y (); pos_vector_3x3 (2 ,1 ) = affine_transform.translation ().x (); pos_vector_3x3 (1 ,2 ) = 0 ;
115+ twist_transform.block (3 ,0 ,3 ,3 ) = pos_vector_3x3 * affine_transform.rotation ();
116+ // lower right 3x3 block is the rotation part
117+ twist_transform.block (3 ,3 ,3 ,3 ) = affine_transform.rotation ();
118+
119+ delta_x = twist_transform * delta_x;
120+ }
121+ catch (tf2::TransformException & ex)
122+ {
123+ RCLCPP_ERROR (node_->get_logger (), " Transformation of wrench failed." );
124+ return false ;
125+ }
126+
127+ std::vector<double > delta_x_v (&delta_x[0 ], delta_x.data () + delta_x.cols () * delta_x.rows ());
128+ delta_x_vec = delta_x_v;
129+
130+ return true ;
87131}
88132
89133} // namespace admittance_controller
0 commit comments