@@ -79,15 +79,15 @@ bool KinematicsInterfaceKDL::initialize(
7979 parameters_interface->get_parameter (ns + " base" , base_param);
8080 root_name_ = base_param.as_string ();
8181 }
82- else
82+ if (root_name_. empty ())
8383 {
8484 root_name_ = robot_tree.getRootSegment ()->first ;
8585 }
8686
8787 if (!robot_tree.getChain (root_name_, end_effector_name, chain_))
8888 {
8989 RCLCPP_ERROR (
90- LOGGER, " failed to find chain from robot root %s to end effector %s " , root_name_.c_str (),
90+ LOGGER, " failed to find chain from robot root '%s' to end effector '%s' " , root_name_.c_str (),
9191 end_effector_name.c_str ());
9292 return false ;
9393 }
@@ -121,6 +121,7 @@ bool KinematicsInterfaceKDL::convert_joint_deltas_to_cartesian_deltas(
121121 !verify_initialized () || !verify_joint_vector (joint_pos) || !verify_link_name (link_name) ||
122122 !verify_joint_vector (delta_theta))
123123 {
124+ RCLCPP_ERROR (LOGGER, " Input verification failed in '%s'" , FUNCTION_SIGNATURE);
124125 return false ;
125126 }
126127
@@ -144,6 +145,7 @@ bool KinematicsInterfaceKDL::convert_cartesian_deltas_to_joint_deltas(
144145 !verify_initialized () || !verify_joint_vector (joint_pos) || !verify_link_name (link_name) ||
145146 !verify_joint_vector (delta_theta))
146147 {
148+ RCLCPP_ERROR (LOGGER, " Input verification failed in '%s'" , FUNCTION_SIGNATURE);
147149 return false ;
148150 }
149151
@@ -167,6 +169,7 @@ bool KinematicsInterfaceKDL::calculate_jacobian(
167169 !verify_initialized () || !verify_joint_vector (joint_pos) || !verify_link_name (link_name) ||
168170 !verify_jacobian (jacobian))
169171 {
172+ RCLCPP_ERROR (LOGGER, " Input verification failed in '%s'" , FUNCTION_SIGNATURE);
170173 return false ;
171174 }
172175
@@ -189,6 +192,7 @@ bool KinematicsInterfaceKDL::calculate_jacobian_inverse(
189192 !verify_initialized () || !verify_joint_vector (joint_pos) || !verify_link_name (link_name) ||
190193 !verify_jacobian_inverse (jacobian_inverse))
191194 {
195+ RCLCPP_ERROR (LOGGER, " Input verification failed in '%s'" , FUNCTION_SIGNATURE);
192196 return false ;
193197 }
194198
@@ -215,6 +219,7 @@ bool KinematicsInterfaceKDL::calculate_link_transform(
215219 // verify inputs
216220 if (!verify_initialized () || !verify_joint_vector (joint_pos) || !verify_link_name (link_name))
217221 {
222+ RCLCPP_ERROR (LOGGER, " Input verification failed in '%s'" , FUNCTION_SIGNATURE);
218223 return false ;
219224 }
220225
@@ -231,8 +236,40 @@ bool KinematicsInterfaceKDL::calculate_link_transform(
231236 }
232237
233238 // create forward kinematics solver
239+ <<<<<<< HEAD
234240 fk_pos_solver_->JntToCart (q_, frame_, link_name_map_[link_name]);
235241 tf2::transformKDLToEigen (frame_, transform);
242+ =======
243+ fk_pos_solver_->JntToCart (q_, frames_ (0 ), link_name_map_[link_name]);
244+ tf2::transformKDLToEigen (frames_ (0 ), transform);
245+ return true ;
246+ }
247+
248+ bool KinematicsInterfaceKDL::calculate_frame_difference (
249+ Eigen::Matrix<double , 7 , 1 > & x_a, Eigen::Matrix<double , 7 , 1 > & x_b, double dt,
250+ Eigen::Matrix<double , 6 , 1 > & delta_x)
251+ {
252+ // verify inputs
253+ if (!verify_period (dt))
254+ {
255+ RCLCPP_ERROR (LOGGER, " Input verification failed in '%s'" , FUNCTION_SIGNATURE);
256+ return false ;
257+ }
258+
259+ // get frames
260+ frames_ (0 ) = KDL::Frame (
261+ 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 )));
262+ frames_ (1 ) = KDL::Frame (
263+ 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 )));
264+
265+ // compute the difference
266+ delta_x_ = KDL::diff (frames_ (0 ), frames_ (1 ), dt);
267+ for (size_t i = 0 ; i < 6 ; ++i)
268+ {
269+ delta_x (static_cast <Eigen::Index>(i)) = delta_x_[static_cast <int >(i)];
270+ }
271+
272+ >>>>>>> 7a77940 (Refactor and extend tests (#210 ))
236273 return true ;
237274}
238275
0 commit comments