@@ -108,6 +108,21 @@ TEST_F(TestKDLPlugin, KDL_plugin_function)
108
108
{
109
109
ASSERT_NEAR (delta_x[i], delta_x_est[i], 0.02 );
110
110
}
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
+ }
111
126
}
112
127
113
128
TEST_F (TestKDLPlugin, KDL_plugin_function_std_vector)
@@ -142,6 +157,21 @@ TEST_F(TestKDLPlugin, KDL_plugin_function_std_vector)
142
157
{
143
158
ASSERT_NEAR (delta_x[i], delta_x_est[i], 0.02 );
144
159
}
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
+ }
145
175
}
146
176
147
177
TEST_F (TestKDLPlugin, incorrect_input_sizes)
@@ -161,10 +191,14 @@ TEST_F(TestKDLPlugin, incorrect_input_sizes)
161
191
delta_x[2 ] = 1 ;
162
192
Eigen::Matrix<double , Eigen::Dynamic, 1 > delta_theta = Eigen::Matrix<double , 2 , 1 >::Zero ();
163
193
Eigen::Matrix<double , 6 , 1 > delta_x_est;
194
+ Eigen::Matrix<double , 7 , 1 > x_a, x_b;
164
195
165
196
// wrong size input vector
166
197
Eigen::Matrix<double , Eigen::Dynamic, 1 > vec_5 = Eigen::Matrix<double , 5 , 1 >::Zero ();
167
198
199
+ // wrong value for period
200
+ double dt = -0.1 ;
201
+
168
202
// calculate transform
169
203
ASSERT_FALSE (ik_->calculate_link_transform (vec_5, end_effector_, end_effector_transform));
170
204
ASSERT_FALSE (ik_->calculate_link_transform (pos, " link_not_in_model" , end_effector_transform));
@@ -183,6 +217,9 @@ TEST_F(TestKDLPlugin, incorrect_input_sizes)
183
217
ik_->convert_joint_deltas_to_cartesian_deltas (pos, vec_5, end_effector_, delta_x_est));
184
218
ASSERT_FALSE (ik_->convert_joint_deltas_to_cartesian_deltas (
185
219
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));
186
223
}
187
224
188
225
TEST_F (TestKDLPlugin, KDL_plugin_no_robot_description)
0 commit comments