Skip to content

Commit 210a57f

Browse files
Add KDL implementation for computing frame differences
1 parent fa0a67f commit 210a57f

File tree

3 files changed

+82
-3
lines changed

3 files changed

+82
-3
lines changed

kinematics_interface_kdl/include/kinematics_interface_kdl/kinematics_interface_kdl.hpp

+7-1
Original file line numberDiff line numberDiff line change
@@ -60,20 +60,26 @@ class KinematicsInterfaceKDL : public kinematics_interface::KinematicsInterface
6060
const Eigen::VectorXd & joint_pos, const std::string & link_name,
6161
Eigen::Matrix<double, 6, Eigen::Dynamic> & jacobian) override;
6262

63+
bool calculate_frame_difference(
64+
Eigen::Matrix<double, 7, 1> & x_a, Eigen::Matrix<double, 7, 1> & x_b, double dt,
65+
Eigen::Matrix<double, 6, 1> & delta_x) override;
66+
6367
private:
6468
// verification methods
6569
bool verify_initialized();
6670
bool verify_link_name(const std::string & link_name);
6771
bool verify_joint_vector(const Eigen::VectorXd & joint_vector);
6872
bool verify_jacobian(const Eigen::Matrix<double, 6, Eigen::Dynamic> & jacobian);
73+
bool verify_period(const double dt);
6974

7075
bool initialized = false;
7176
std::string root_name_;
7277
size_t num_joints_;
7378
KDL::Chain chain_;
7479
std::shared_ptr<KDL::ChainFkSolverPos_recursive> fk_pos_solver_;
7580
KDL::JntArray q_;
76-
KDL::Frame frame_;
81+
Eigen::Matrix<KDL::Frame, 2, 1> frames_;
82+
KDL::Twist delta_x_;
7783
std::shared_ptr<KDL::Jacobian> jacobian_;
7884
std::shared_ptr<KDL::ChainJntToJacSolver> jac_solver_;
7985
std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface> parameters_interface_;

kinematics_interface_kdl/src/kinematics_interface_kdl.cpp

+38-2
Original file line numberDiff line numberDiff line change
@@ -205,8 +205,34 @@ bool KinematicsInterfaceKDL::calculate_link_transform(
205205
}
206206

207207
// create forward kinematics solver
208-
fk_pos_solver_->JntToCart(q_, frame_, link_name_map_[link_name]);
209-
tf2::transformKDLToEigen(frame_, transform);
208+
fk_pos_solver_->JntToCart(q_, frames_(0), link_name_map_[link_name]);
209+
tf2::transformKDLToEigen(frames_(0), transform);
210+
return true;
211+
}
212+
213+
bool KinematicsInterfaceKDL::calculate_frame_difference(
214+
Eigen::Matrix<double, 7, 1> & x_a, Eigen::Matrix<double, 7, 1> & x_b, double dt,
215+
Eigen::Matrix<double, 6, 1> & delta_x)
216+
{
217+
// verify inputs
218+
if (!verify_initialized() || !verify_period(dt))
219+
{
220+
return false;
221+
}
222+
223+
// get frames
224+
frames_(0) = KDL::Frame(
225+
KDL::Rotation::Quaternion(x_a(3), x_a(4), x_a(5), x_a(6)), KDL::Vector(x_a(0), x_a(1), x_a(2)));
226+
frames_(1) = KDL::Frame(
227+
KDL::Rotation::Quaternion(x_b(3), x_b(4), x_b(5), x_b(6)), KDL::Vector(x_b(0), x_b(1), x_b(2)));
228+
229+
// compute the difference
230+
delta_x_ = KDL::diff(frames_(0), frames_(1), dt);
231+
for (size_t i = 0; i < 6; ++i)
232+
{
233+
delta_x(i) = delta_x_[i];
234+
}
235+
210236
return true;
211237
}
212238

@@ -269,6 +295,16 @@ bool KinematicsInterfaceKDL::verify_jacobian(
269295
return true;
270296
}
271297

298+
bool KinematicsInterfaceKDL::verify_period(const double dt)
299+
{
300+
if (dt < 0)
301+
{
302+
RCLCPP_ERROR(LOGGER, "The period (%f) must be a non-negative number", dt);
303+
return false;
304+
}
305+
return true;
306+
}
307+
272308
} // namespace kinematics_interface_kdl
273309

274310
#include "pluginlib/class_list_macros.hpp"

kinematics_interface_kdl/test/test_kinematics_interface_kdl.cpp

+37
Original file line numberDiff line numberDiff line change
@@ -108,6 +108,21 @@ TEST_F(TestKDLPlugin, KDL_plugin_function)
108108
{
109109
ASSERT_NEAR(delta_x[i], delta_x_est[i], 0.02);
110110
}
111+
112+
// compute the difference between two cartesian frames
113+
Eigen::Matrix<double, 7, 1> x_a, x_b;
114+
x_a << 0, 1, 0, 0, 0, 0, 1;
115+
x_b << 2, 3, 0, 0, 1, 0, 0;
116+
double dt = 1.0;
117+
delta_x = Eigen::Matrix<double, 6, 1>::Zero();
118+
delta_x_est << 2, 2, 0, 0, 3.14, 0;
119+
ASSERT_TRUE(ik_->calculate_frame_difference(x_a, x_b, dt, delta_x));
120+
121+
// ensure that difference math is correct
122+
for (size_t i = 0; i < static_cast<size_t>(delta_x.size()); ++i)
123+
{
124+
ASSERT_NEAR(delta_x(i), delta_x_est(i), 0.02);
125+
}
111126
}
112127

113128
TEST_F(TestKDLPlugin, KDL_plugin_function_std_vector)
@@ -142,6 +157,21 @@ TEST_F(TestKDLPlugin, KDL_plugin_function_std_vector)
142157
{
143158
ASSERT_NEAR(delta_x[i], delta_x_est[i], 0.02);
144159
}
160+
161+
// compute the difference between two cartesian frames
162+
std::vector<double> x_a(7), x_b(7);
163+
x_a = {0, 1, 0, 0, 0, 0, 1};
164+
x_b = {2, 3, 0, 0, 1, 0, 0};
165+
double dt = 1.0;
166+
delta_x = {0, 0, 0, 0, 0, 0};
167+
delta_x_est = {2, 2, 0, 0, 3.14, 0};
168+
ASSERT_TRUE(ik_->calculate_frame_difference(x_a, x_b, dt, delta_x));
169+
170+
// ensure that difference math is correct
171+
for (size_t i = 0; i < static_cast<size_t>(delta_x.size()); ++i)
172+
{
173+
ASSERT_NEAR(delta_x[i], delta_x_est[i], 0.02);
174+
}
145175
}
146176

147177
TEST_F(TestKDLPlugin, incorrect_input_sizes)
@@ -161,10 +191,14 @@ TEST_F(TestKDLPlugin, incorrect_input_sizes)
161191
delta_x[2] = 1;
162192
Eigen::Matrix<double, Eigen::Dynamic, 1> delta_theta = Eigen::Matrix<double, 2, 1>::Zero();
163193
Eigen::Matrix<double, 6, 1> delta_x_est;
194+
Eigen::Matrix<double, 7, 1> x_a, x_b;
164195

165196
// wrong size input vector
166197
Eigen::Matrix<double, Eigen::Dynamic, 1> vec_5 = Eigen::Matrix<double, 5, 1>::Zero();
167198

199+
// wrong value for period
200+
double dt = -0.1;
201+
168202
// calculate transform
169203
ASSERT_FALSE(ik_->calculate_link_transform(vec_5, end_effector_, end_effector_transform));
170204
ASSERT_FALSE(ik_->calculate_link_transform(pos, "link_not_in_model", end_effector_transform));
@@ -183,6 +217,9 @@ TEST_F(TestKDLPlugin, incorrect_input_sizes)
183217
ik_->convert_joint_deltas_to_cartesian_deltas(pos, vec_5, end_effector_, delta_x_est));
184218
ASSERT_FALSE(ik_->convert_joint_deltas_to_cartesian_deltas(
185219
pos, delta_theta, "link_not_in_model", delta_x_est));
220+
221+
// compute the difference between two cartesian frames
222+
ASSERT_FALSE(ik_->calculate_frame_difference(x_a, x_b, dt, delta_x));
186223
}
187224

188225
TEST_F(TestKDLPlugin, KDL_plugin_no_robot_description)

0 commit comments

Comments
 (0)