36 const std::shared_ptr<rclcpp_lifecycle::LifecycleNode> & node,
const size_t num_joints)
38 num_joints_ = num_joints;
44 if (!parameters_.kinematics.plugin_name.empty())
49 if (kinematics_loader_)
54 std::make_shared<pluginlib::ClassLoader<kinematics_interface::KinematicsInterface>>(
55 parameters_.kinematics.plugin_package,
"kinematics_interface::KinematicsInterface");
56 kinematics_ = std::unique_ptr<kinematics_interface::KinematicsInterface>(
57 kinematics_loader_->createUnmanagedInstance(parameters_.kinematics.plugin_name));
59 if (!kinematics_->initialize(
60 node->get_node_parameters_interface(), parameters_.kinematics.tip))
62 return controller_interface::return_type::ERROR;
65 catch (pluginlib::PluginlibException & ex)
68 rclcpp::get_logger(
"AdmittanceRule"),
"Exception while loading the IK plugin '%s': '%s'",
69 parameters_.kinematics.plugin_name.c_str(), ex.what());
70 return controller_interface::return_type::ERROR;
76 rclcpp::get_logger(
"AdmittanceRule"),
77 "A differential IK plugin name was not specified in the config file.");
78 return controller_interface::return_type::ERROR;
81 return controller_interface::return_type::OK;
87 state_message_.joint_state.name.assign(num_joints,
"");
88 state_message_.joint_state.position.assign(num_joints, 0);
89 state_message_.joint_state.velocity.assign(num_joints, 0);
90 state_message_.joint_state.effort.assign(num_joints, 0);
91 for (
size_t i = 0; i < parameters_.joints.size(); ++i)
93 state_message_.joint_state.name = parameters_.joints;
95 state_message_.mass.data.resize(NUM_CARTESIAN_DOF, 0.0);
96 state_message_.selected_axes.data.resize(NUM_CARTESIAN_DOF, 0);
97 state_message_.damping.data.resize(NUM_CARTESIAN_DOF, 0);
98 state_message_.stiffness.data.resize(NUM_CARTESIAN_DOF, 0);
99 state_message_.wrench_base.header.frame_id = parameters_.kinematics.base;
100 state_message_.admittance_velocity.header.frame_id = parameters_.kinematics.base;
101 state_message_.admittance_acceleration.header.frame_id = parameters_.kinematics.base;
102 state_message_.admittance_position.header.frame_id = parameters_.kinematics.base;
103 state_message_.admittance_position.child_frame_id =
"admittance_offset";
112 wrench_world_.setZero();
113 end_effector_weight_.setZero();
118 return controller_interface::return_type::OK;
145 const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state,
146 const trajectory_msgs::msg::JointTrajectoryPoint & reference_joint_state)
149 bool success = kinematics_->calculate_link_transform(
150 reference_joint_state.positions, parameters_.ft_sensor.frame.id,
151 admittance_transforms_.ref_base_ft_);
154 success &= kinematics_->calculate_link_transform(
155 current_joint_state.positions, parameters_.ft_sensor.frame.id, admittance_transforms_.base_ft_);
156 success &= kinematics_->calculate_link_transform(
157 current_joint_state.positions, parameters_.kinematics.tip, admittance_transforms_.base_tip_);
158 success &= kinematics_->calculate_link_transform(
159 current_joint_state.positions, parameters_.fixed_world_frame.frame.id,
160 admittance_transforms_.world_base_);
161 success &= kinematics_->calculate_link_transform(
162 current_joint_state.positions, parameters_.gravity_compensation.frame.id,
163 admittance_transforms_.base_cog_);
164 success &= kinematics_->calculate_link_transform(
165 current_joint_state.positions, parameters_.control.frame.id,
166 admittance_transforms_.base_control_);
173 const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state,
174 const geometry_msgs::msg::Wrench & measured_wrench,
175 const trajectory_msgs::msg::JointTrajectoryPoint & reference_joint_state,
176 const rclcpp::Duration & period, trajectory_msgs::msg::JointTrajectoryPoint & desired_joint_state)
178 const double dt = period.seconds();
180 if (parameters_.enable_parameter_update_without_reactivation)
188 Eigen::Matrix<double, 3, 3> rot_world_sensor =
189 admittance_transforms_.world_base_.rotation() * admittance_transforms_.base_ft_.rotation();
190 Eigen::Matrix<double, 3, 3> rot_world_cog =
191 admittance_transforms_.world_base_.rotation() * admittance_transforms_.base_cog_.rotation();
195 admittance_state_.wrench_base.block<3, 1>(0, 0) =
196 admittance_transforms_.world_base_.rotation().transpose() * wrench_world_.block<3, 1>(0, 0);
197 admittance_state_.wrench_base.block<3, 1>(3, 0) =
198 admittance_transforms_.world_base_.rotation().transpose() * wrench_world_.block<3, 1>(3, 0);
201 vec_to_eigen(current_joint_state.positions, admittance_state_.current_joint_pos);
202 admittance_state_.rot_base_control = admittance_transforms_.base_control_.rotation();
203 admittance_state_.ref_trans_base_ft = admittance_transforms_.ref_base_ft_;
204 admittance_state_.ft_sensor_frame = parameters_.ft_sensor.frame.id;
211 desired_joint_state = reference_joint_state;
212 return controller_interface::return_type::ERROR;
216 for (
size_t i = 0; i < num_joints_; ++i)
218 auto idx =
static_cast<Eigen::Index
>(i);
219 desired_joint_state.positions[i] =
220 reference_joint_state.positions[i] + admittance_state_.joint_pos[idx];
221 desired_joint_state.velocities[i] =
222 reference_joint_state.velocities[i] + admittance_state_.joint_vel[idx];
223 desired_joint_state.accelerations[i] =
224 reference_joint_state.accelerations[i] + admittance_state_.joint_acc[idx];
227 return controller_interface::return_type::OK;
234 auto rot_base_control = admittance_state.rot_base_control;
235 Eigen::Matrix<double, 6, 6> K = Eigen::Matrix<double, 6, 6>::Zero();
236 Eigen::Matrix<double, 3, 3> K_pos = Eigen::Matrix<double, 3, 3>::Zero();
237 Eigen::Matrix<double, 3, 3> K_rot = Eigen::Matrix<double, 3, 3>::Zero();
238 K_pos.diagonal() = admittance_state.stiffness.block<3, 1>(0, 0);
239 K_rot.diagonal() = admittance_state.stiffness.block<3, 1>(3, 0);
244 K_pos = rot_base_control * K_pos * rot_base_control.transpose();
245 K_rot = rot_base_control * K_rot * rot_base_control.transpose();
246 K.block<3, 3>(0, 0) = K_pos;
247 K.block<3, 3>(3, 3) = K_rot;
250 Eigen::Matrix<double, 6, 6> D = Eigen::Matrix<double, 6, 6>::Zero();
251 Eigen::Matrix<double, 3, 3> D_pos = Eigen::Matrix<double, 3, 3>::Zero();
252 Eigen::Matrix<double, 3, 3> D_rot = Eigen::Matrix<double, 3, 3>::Zero();
253 D_pos.diagonal() = admittance_state.damping.block<3, 1>(0, 0);
254 D_rot.diagonal() = admittance_state.damping.block<3, 1>(3, 0);
255 D_pos = rot_base_control * D_pos * rot_base_control.transpose();
256 D_rot = rot_base_control * D_rot * rot_base_control.transpose();
257 D.block<3, 3>(0, 0) = D_pos;
258 D.block<3, 3>(3, 3) = D_rot;
261 Eigen::Isometry3d desired_trans_base_ft;
262 kinematics_->calculate_link_transform(
263 admittance_state.current_joint_pos, admittance_state.ft_sensor_frame, desired_trans_base_ft);
264 Eigen::Matrix<double, 6, 1> X;
265 X.block<3, 1>(0, 0) =
266 desired_trans_base_ft.translation() - admittance_state.ref_trans_base_ft.translation();
267 auto R_ref = admittance_state.ref_trans_base_ft.rotation();
268 auto R_desired = desired_trans_base_ft.rotation();
269 auto R = R_desired * R_ref.transpose();
270 auto angle_axis = Eigen::AngleAxisd(R);
271 X.block<3, 1>(3, 0) = angle_axis.angle() * angle_axis.axis();
274 auto X_dot = Eigen::Matrix<double, 6, 1>(admittance_state.admittance_velocity.data());
277 auto F_base = admittance_state.wrench_base;
280 Eigen::Matrix<double, 6, 1> F_control;
281 F_control.block<3, 1>(0, 0) = rot_base_control.transpose() * F_base.block<3, 1>(0, 0);
282 F_control.block<3, 1>(3, 0) = rot_base_control.transpose() * F_base.block<3, 1>(3, 0);
283 F_control = F_control.cwiseProduct(admittance_state.selected_axes);
284 F_base.block<3, 1>(0, 0) = rot_base_control * F_control.block<3, 1>(0, 0);
285 F_base.block<3, 1>(3, 0) = rot_base_control * F_control.block<3, 1>(3, 0);
288 Eigen::Matrix<double, 6, 1> X_ddot =
289 admittance_state.mass_inv.cwiseProduct(F_base - D * X_dot - K * X);
290 bool success = kinematics_->convert_cartesian_deltas_to_joint_deltas(
291 admittance_state.current_joint_pos, X_ddot, admittance_state.ft_sensor_frame,
292 admittance_state.joint_acc);
295 for (int64_t i = 0; i < admittance_state.joint_acc.size(); ++i)
297 admittance_state.joint_acc[i] -=
298 parameters_.admittance.joint_damping * admittance_state.joint_vel[i];
302 admittance_state.joint_vel += (admittance_state.joint_acc) * dt;
303 admittance_state.joint_pos += admittance_state.joint_vel * dt;
306 success &= kinematics_->convert_joint_deltas_to_cartesian_deltas(
307 admittance_state.current_joint_pos, admittance_state.joint_vel,
308 admittance_state.ft_sensor_frame, admittance_state.admittance_velocity);
309 success &= kinematics_->convert_joint_deltas_to_cartesian_deltas(
310 admittance_state.current_joint_pos, admittance_state.joint_acc,
311 admittance_state.ft_sensor_frame, admittance_state.admittance_acceleration);
317 const geometry_msgs::msg::Wrench & measured_wrench,
318 const Eigen::Matrix<double, 3, 3> & sensor_world_rot,
319 const Eigen::Matrix<double, 3, 3> & cog_world_rot)
321 Eigen::Matrix<double, 3, 2, Eigen::ColMajor> new_wrench;
322 new_wrench(0, 0) = measured_wrench.force.x;
323 new_wrench(1, 0) = measured_wrench.force.y;
324 new_wrench(2, 0) = measured_wrench.force.z;
325 new_wrench(0, 1) = measured_wrench.torque.x;
326 new_wrench(1, 1) = measured_wrench.torque.y;
327 new_wrench(2, 1) = measured_wrench.torque.z;
330 Eigen::Matrix<double, 3, 2> new_wrench_base = sensor_world_rot * new_wrench;
333 new_wrench_base(2, 0) -= end_effector_weight_[2];
334 new_wrench_base.block<3, 1>(0, 1) -= (cog_world_rot * cog_pos_).cross(end_effector_weight_);
337 for (Eigen::Index i = 0; i < 6; ++i)
339 wrench_world_(i) = filters::exponentialSmoothing(
340 new_wrench_base(i), wrench_world_(i), parameters_.ft_sensor.filter_coefficient);
346 for (
size_t i = 0; i < NUM_CARTESIAN_DOF; ++i)
348 auto idx =
static_cast<Eigen::Index
>(i);
349 state_message_.stiffness.data[i] = admittance_state_.stiffness[idx];
350 state_message_.damping.data[i] = admittance_state_.damping[idx];
351 state_message_.selected_axes.data[i] =
static_cast<bool>(admittance_state_.selected_axes[idx]);
352 state_message_.mass.data[i] = admittance_state_.mass[idx];
355 for (
size_t i = 0; i < parameters_.joints.size(); ++i)
357 auto idx =
static_cast<Eigen::Index
>(i);
358 state_message_.joint_state.name[i] = parameters_.joints[i];
359 state_message_.joint_state.position[i] = admittance_state_.joint_pos[idx];
360 state_message_.joint_state.velocity[i] = admittance_state_.joint_vel[idx];
361 state_message_.joint_state.effort[i] = admittance_state_.joint_acc[idx];
364 state_message_.wrench_base.wrench.force.x = admittance_state_.wrench_base[0];
365 state_message_.wrench_base.wrench.force.y = admittance_state_.wrench_base[1];
366 state_message_.wrench_base.wrench.force.z = admittance_state_.wrench_base[2];
367 state_message_.wrench_base.wrench.torque.x = admittance_state_.wrench_base[3];
368 state_message_.wrench_base.wrench.torque.y = admittance_state_.wrench_base[4];
369 state_message_.wrench_base.wrench.torque.z = admittance_state_.wrench_base[5];
371 state_message_.admittance_velocity.twist.linear.x = admittance_state_.admittance_velocity[0];
372 state_message_.admittance_velocity.twist.linear.y = admittance_state_.admittance_velocity[1];
373 state_message_.admittance_velocity.twist.linear.z = admittance_state_.admittance_velocity[2];
374 state_message_.admittance_velocity.twist.angular.x = admittance_state_.admittance_velocity[3];
375 state_message_.admittance_velocity.twist.angular.y = admittance_state_.admittance_velocity[4];
376 state_message_.admittance_velocity.twist.angular.z = admittance_state_.admittance_velocity[5];
378 state_message_.admittance_acceleration.twist.linear.x =
379 admittance_state_.admittance_acceleration[0];
380 state_message_.admittance_acceleration.twist.linear.y =
381 admittance_state_.admittance_acceleration[1];
382 state_message_.admittance_acceleration.twist.linear.z =
383 admittance_state_.admittance_acceleration[2];
384 state_message_.admittance_acceleration.twist.angular.x =
385 admittance_state_.admittance_acceleration[3];
386 state_message_.admittance_acceleration.twist.angular.y =
387 admittance_state_.admittance_acceleration[4];
388 state_message_.admittance_acceleration.twist.angular.z =
389 admittance_state_.admittance_acceleration[5];
391 state_message_.admittance_position = tf2::eigenToTransform(admittance_state_.admittance_position);
393 state_message_.ref_trans_base_ft.header.frame_id = parameters_.kinematics.base;
394 state_message_.ref_trans_base_ft.header.frame_id =
"ft_reference";
395 state_message_.ref_trans_base_ft = tf2::eigenToTransform(admittance_state_.ref_trans_base_ft);
397 Eigen::Quaterniond quat(admittance_state_.rot_base_control);
398 state_message_.rot_base_control.w = quat.w();
399 state_message_.rot_base_control.x = quat.x();
400 state_message_.rot_base_control.y = quat.y();
401 state_message_.rot_base_control.z = quat.z();
403 state_message_.ft_sensor_frame.data =
404 admittance_state_.ft_sensor_frame;
406 return state_message_;