Skip to content

Commit 221349b

Browse files
authored
Finish the method for forward kinematics (#4)
* Rename incremental_ik_calculator -> incremental_kinematics * Use Eigen double types. Rename _trafo transform variables * Fix typo in transformation matrix * Implement incremental forward kinematics
1 parent 8f554b2 commit 221349b

File tree

6 files changed

+65
-21
lines changed

6 files changed

+65
-21
lines changed

admittance_controller/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,7 @@ add_library(
3333
SHARED
3434
src/admittance_controller.cpp
3535
src/admittance_rule.cpp
36-
src/incremental_ik_calculator.cpp
36+
src/incremental_kinematics.cpp
3737
)
3838
target_include_directories(
3939
admittance_controller

admittance_controller/include/admittance_controller/admittance_rule.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,7 @@
1717
#ifndef ADMITTANCE_CONTROLLER__ADMITTANCE_RULE_HPP_
1818
#define ADMITTANCE_CONTROLLER__ADMITTANCE_RULE_HPP_
1919

20-
#include "admittance_controller/incremental_ik_calculator.hpp"
20+
#include "admittance_controller/incremental_kinematics.hpp"
2121
#include "control_msgs/msg/admittance_controller_state.hpp"
2222
#include "controller_interface/controller_interface.hpp"
2323
#include "geometry_msgs/msg/quaternion.hpp"
@@ -86,7 +86,7 @@ class AdmittanceRule
8686

8787
protected:
8888
// IK variables
89-
std::shared_ptr<IncrementalIKCalculator> ik_;
89+
std::shared_ptr<IncrementalKinematics> ik_;
9090
Eigen::VectorXd delta_x_;
9191
Eigen::VectorXd delta_theta_;
9292

admittance_controller/include/admittance_controller/incremental_ik_calculator.hpp renamed to admittance_controller/include/admittance_controller/incremental_kinematics.hpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -25,34 +25,34 @@
2525
namespace admittance_controller
2626
{
2727

28-
class IncrementalIKCalculator
28+
class IncrementalKinematics
2929
{
3030
public:
3131
/**
3232
* \brief Create an object which takes Cartesian delta-x and converts to joint delta-theta.
3333
* It uses the Jacobian from MoveIt.
3434
*/
35-
IncrementalIKCalculator(const std::shared_ptr<rclcpp::Node> & node, const std::string & group_name);
35+
IncrementalKinematics(const std::shared_ptr<rclcpp::Node> & node, const std::string & group_name);
3636

3737
/**
3838
* \brief Convert Cartesian delta-x to joint delta-theta, using the Jacobian.
3939
* \param delta_x_vec input Cartesian deltas (x, y, z, rx, ry, rz)
40-
* \param ik_base_to_tip_trafo transformation between ik base and ik tip
40+
* \param ik_base_to_tip_tf transformation between ik base and ik tip
4141
* \param delta_theta_vec output vector with joint states
4242
* \return true if successful
4343
*/
4444
bool
45-
convertCartesianDeltasToJointDeltas(const std::vector<double> & delta_x_vec, const geometry_msgs::msg::TransformStamped & ik_base_to_tip_trafo, std::vector<double> & delta_theta_vec);
45+
convertCartesianDeltasToJointDeltas(const std::vector<double> & delta_x_vec, const geometry_msgs::msg::TransformStamped & ik_base_to_tip_tf, std::vector<double> & delta_theta_vec);
4646

4747
/**
4848
* \brief Convert joint delta-theta to Cartesian delta-x, using the Jacobian.
4949
* \param[in] delta_theta_vec vector with joint states
50-
* \param[in] ik_base_to_tip_trafo transformation between ik base to ik tip
50+
* \param[in] ik_base_to_tip_tf transformation between ik base to ik tip
5151
* \param[out] delta_x_vec Cartesian deltas (x, y, z, rx, ry, rz)
5252
* \return true if successful
5353
*/
5454
bool
55-
convertJointDeltasToCartesianDeltas(const std::vector<double> & delta_theta_vec, const geometry_msgs::msg::TransformStamped & ik_base_to_tip_trafo, std::vector<double> & delta_x_vec);
55+
convertJointDeltasToCartesianDeltas(const std::vector<double> & delta_theta_vec, const geometry_msgs::msg::TransformStamped & ik_base_to_tip_tf, std::vector<double> & delta_x_vec);
5656

5757
private:
5858
// MoveIt setup, required to retrieve the Jacobian

admittance_controller/src/admittance_controller.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@
2222
// #include "Eigen/Core"
2323

2424
#include "admittance_controller/admittance_controller.hpp"
25-
#include "admittance_controller/incremental_ik_calculator.hpp"
25+
#include "admittance_controller/incremental_kinematics.hpp"
2626
#include "controller_interface/helpers.hpp"
2727
#include "hardware_interface/types/hardware_interface_type_values.hpp"
2828

admittance_controller/src/admittance_rule.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -156,7 +156,7 @@ controller_interface::return_type AdmittanceRule::configure(rclcpp::Node::Shared
156156
relative_desired_joint_state_vec_.reserve(6);
157157

158158
// Initialize IK
159-
ik_ = std::make_shared<IncrementalIKCalculator>(node, ik_group_name_);
159+
ik_ = std::make_shared<IncrementalKinematics>(node, ik_group_name_);
160160

161161
return controller_interface::return_type::OK;
162162
}

admittance_controller/src/incremental_ik_calculator.cpp renamed to admittance_controller/src/incremental_kinematics.cpp

Lines changed: 54 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -14,14 +14,14 @@
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

2222
namespace 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

Comments
 (0)