ros2_control - rolling
admittance_rule_impl.hpp
1 // Copyright (c) 2022, PickNik, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 //
16 
17 #ifndef ADMITTANCE_CONTROLLER__ADMITTANCE_RULE_IMPL_HPP_
18 #define ADMITTANCE_CONTROLLER__ADMITTANCE_RULE_IMPL_HPP_
19 
20 #include "admittance_controller/admittance_rule.hpp"
21 
22 #include <memory>
23 #include <string>
24 #include <vector>
25 
26 #include <control_toolbox/filters.hpp>
27 #include <tf2_eigen/tf2_eigen.hpp>
28 
29 #include "rclcpp/duration.hpp"
30 
31 namespace admittance_controller
32 {
33 
34 constexpr auto NUM_CARTESIAN_DOF = 6; // (3 translation + 3 rotation)
35 
37 controller_interface::return_type AdmittanceRule::configure(
38  const std::shared_ptr<rclcpp_lifecycle::LifecycleNode> & node, const size_t num_joints,
39  const std::string & robot_description)
40 {
41  num_joints_ = num_joints;
42 
43  // initialize memory and values to zero (non-realtime function)
44  reset(num_joints);
45 
46  // Load the differential IK plugin
47  if (!parameters_.kinematics.plugin_name.empty())
48  {
49  try
50  {
51  // Make sure we destroy the interface first. Otherwise we might run into a segfault
52  if (kinematics_loader_)
53  {
54  kinematics_.reset();
55  }
56  kinematics_loader_ =
57  std::make_shared<pluginlib::ClassLoader<kinematics_interface::KinematicsInterface>>(
58  parameters_.kinematics.plugin_package, "kinematics_interface::KinematicsInterface");
59  kinematics_ = std::unique_ptr<kinematics_interface::KinematicsInterface>(
60  kinematics_loader_->createUnmanagedInstance(parameters_.kinematics.plugin_name));
61 
62  if (!kinematics_->initialize(
63  robot_description, node->get_node_parameters_interface(), "kinematics"))
64  {
65  return controller_interface::return_type::ERROR;
66  }
67  }
68  catch (pluginlib::PluginlibException & ex)
69  {
70  RCLCPP_ERROR(
71  rclcpp::get_logger("AdmittanceRule"), "Exception while loading the IK plugin '%s': '%s'",
72  parameters_.kinematics.plugin_name.c_str(), ex.what());
73  return controller_interface::return_type::ERROR;
74  }
75  }
76  else
77  {
78  RCLCPP_ERROR(
79  rclcpp::get_logger("AdmittanceRule"),
80  "A differential IK plugin name was not specified in the config file.");
81  return controller_interface::return_type::ERROR;
82  }
83 
84  return controller_interface::return_type::OK;
85 }
86 
87 controller_interface::return_type AdmittanceRule::reset(const size_t num_joints)
88 {
89  // reset state message fields
90  state_message_.joint_state.name.assign(num_joints, "");
91  state_message_.joint_state.position.assign(num_joints, 0);
92  state_message_.joint_state.velocity.assign(num_joints, 0);
93  state_message_.joint_state.effort.assign(num_joints, 0);
94  for (size_t i = 0; i < parameters_.joints.size(); ++i)
95  {
96  state_message_.joint_state.name = parameters_.joints;
97  }
98  state_message_.mass.data.resize(NUM_CARTESIAN_DOF, 0.0);
99  state_message_.selected_axes.data.resize(NUM_CARTESIAN_DOF, 0);
100  state_message_.damping.data.resize(NUM_CARTESIAN_DOF, 0);
101  state_message_.stiffness.data.resize(NUM_CARTESIAN_DOF, 0);
102  state_message_.wrench_base.header.frame_id = parameters_.kinematics.base;
103  state_message_.admittance_velocity.header.frame_id = parameters_.kinematics.base;
104  state_message_.admittance_acceleration.header.frame_id = parameters_.kinematics.base;
105  state_message_.admittance_position.header.frame_id = parameters_.kinematics.base;
106  state_message_.admittance_position.child_frame_id = "admittance_offset";
107 
108  // reset admittance state
109  admittance_state_ = AdmittanceState(num_joints);
110 
111  // reset transforms and rotations
112  admittance_transforms_ = AdmittanceTransforms();
113 
114  // reset forces
115  wrench_world_.setZero();
116  end_effector_weight_.setZero();
117 
118  // load/initialize Eigen types from parameters
120 
121  return controller_interface::return_type::OK;
122 }
123 
125 {
126  if (parameter_handler_->is_old(parameters_))
127  {
128  parameters_ = parameter_handler_->get_params();
129  }
130  // update param values
131  end_effector_weight_[2] = -parameters_.gravity_compensation.CoG.force;
132  vec_to_eigen(parameters_.gravity_compensation.CoG.pos, cog_pos_);
133  vec_to_eigen(parameters_.admittance.mass, admittance_state_.mass);
134  vec_to_eigen(parameters_.admittance.stiffness, admittance_state_.stiffness);
135  vec_to_eigen(parameters_.admittance.selected_axes, admittance_state_.selected_axes);
136 
137  for (size_t i = 0; i < NUM_CARTESIAN_DOF; ++i)
138  {
139  auto idx = static_cast<Eigen::Index>(i);
140  admittance_state_.mass_inv[idx] = 1.0 / parameters_.admittance.mass[i];
141  admittance_state_.damping[idx] =
142  parameters_.admittance.damping_ratio[i] * 2 *
143  sqrt(admittance_state_.mass[idx] * admittance_state_.stiffness[idx]);
144  }
145 }
146 
148  const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state,
149  const trajectory_msgs::msg::JointTrajectoryPoint & reference_joint_state)
150 {
151  // get reference transforms
152  bool success = kinematics_->calculate_link_transform(
153  reference_joint_state.positions, parameters_.ft_sensor.frame.id,
154  admittance_transforms_.ref_base_ft_);
155 
156  // get transforms at current configuration
157  success &= kinematics_->calculate_link_transform(
158  current_joint_state.positions, parameters_.ft_sensor.frame.id, admittance_transforms_.base_ft_);
159  success &= kinematics_->calculate_link_transform(
160  current_joint_state.positions, parameters_.kinematics.tip, admittance_transforms_.base_tip_);
161  success &= kinematics_->calculate_link_transform(
162  current_joint_state.positions, parameters_.fixed_world_frame.frame.id,
163  admittance_transforms_.world_base_);
164  success &= kinematics_->calculate_link_transform(
165  current_joint_state.positions, parameters_.gravity_compensation.frame.id,
166  admittance_transforms_.base_cog_);
167  success &= kinematics_->calculate_link_transform(
168  current_joint_state.positions, parameters_.control.frame.id,
169  admittance_transforms_.base_control_);
170 
171  return success;
172 }
173 
174 // Update from reference joint states
175 controller_interface::return_type AdmittanceRule::update(
176  const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state,
177  const geometry_msgs::msg::Wrench & measured_wrench,
178  const trajectory_msgs::msg::JointTrajectoryPoint & reference_joint_state,
179  const rclcpp::Duration & period, trajectory_msgs::msg::JointTrajectoryPoint & desired_joint_state)
180 {
181  const double dt = period.seconds();
182 
183  if (parameters_.enable_parameter_update_without_reactivation)
184  {
186  }
187 
188  bool success = get_all_transforms(current_joint_state, reference_joint_state);
189 
190  // apply filter and update wrench_world_ vector
191  Eigen::Matrix<double, 3, 3> rot_world_sensor =
192  admittance_transforms_.world_base_.rotation() * admittance_transforms_.base_ft_.rotation();
193  Eigen::Matrix<double, 3, 3> rot_world_cog =
194  admittance_transforms_.world_base_.rotation() * admittance_transforms_.base_cog_.rotation();
195  process_wrench_measurements(measured_wrench, rot_world_sensor, rot_world_cog);
196 
197  // transform wrench_world_ into base frame
198  admittance_state_.wrench_base.block<3, 1>(0, 0) =
199  admittance_transforms_.world_base_.rotation().transpose() * wrench_world_.block<3, 1>(0, 0);
200  admittance_state_.wrench_base.block<3, 1>(3, 0) =
201  admittance_transforms_.world_base_.rotation().transpose() * wrench_world_.block<3, 1>(3, 0);
202 
203  // Compute admittance control law
204  vec_to_eigen(current_joint_state.positions, admittance_state_.current_joint_pos);
205  admittance_state_.rot_base_control = admittance_transforms_.base_control_.rotation();
206  admittance_state_.ref_trans_base_ft = admittance_transforms_.ref_base_ft_;
207  admittance_state_.ft_sensor_frame = parameters_.ft_sensor.frame.id;
208  success &= calculate_admittance_rule(admittance_state_, dt);
209 
210  // if a failure occurred during any kinematics interface calls, return an error and don't
211  // modify the desired reference
212  if (!success)
213  {
214  desired_joint_state = reference_joint_state;
215  return controller_interface::return_type::ERROR;
216  }
217 
218  // update joint desired joint state
219  for (size_t i = 0; i < num_joints_; ++i)
220  {
221  auto idx = static_cast<Eigen::Index>(i);
222  desired_joint_state.positions[i] =
223  reference_joint_state.positions[i] + admittance_state_.joint_pos[idx];
224  desired_joint_state.velocities[i] =
225  reference_joint_state.velocities[i] + admittance_state_.joint_vel[idx];
226  desired_joint_state.accelerations[i] =
227  reference_joint_state.accelerations[i] + admittance_state_.joint_acc[idx];
228  }
229 
230  return controller_interface::return_type::OK;
231 }
232 
234 {
235  // Create stiffness matrix in base frame. The user-provided values of admittance_state.stiffness
236  // correspond to the six diagonal elements of the stiffness matrix expressed in the control frame
237  auto rot_base_control = admittance_state.rot_base_control;
238  Eigen::Matrix<double, 6, 6> K = Eigen::Matrix<double, 6, 6>::Zero();
239  Eigen::Matrix<double, 3, 3> K_pos = Eigen::Matrix<double, 3, 3>::Zero();
240  Eigen::Matrix<double, 3, 3> K_rot = Eigen::Matrix<double, 3, 3>::Zero();
241  K_pos.diagonal() = admittance_state.stiffness.block<3, 1>(0, 0);
242  K_rot.diagonal() = admittance_state.stiffness.block<3, 1>(3, 0);
243  // Transform to the control frame
244  // A reference is here: https://users.wpi.edu/~jfu2/rbe502/files/force_control.pdf
245  // Force Control by Luigi Villani and Joris De Schutter
246  // Page 200
247  K_pos = rot_base_control * K_pos * rot_base_control.transpose();
248  K_rot = rot_base_control * K_rot * rot_base_control.transpose();
249  K.block<3, 3>(0, 0) = K_pos;
250  K.block<3, 3>(3, 3) = K_rot;
251 
252  // The same for damping
253  Eigen::Matrix<double, 6, 6> D = Eigen::Matrix<double, 6, 6>::Zero();
254  Eigen::Matrix<double, 3, 3> D_pos = Eigen::Matrix<double, 3, 3>::Zero();
255  Eigen::Matrix<double, 3, 3> D_rot = Eigen::Matrix<double, 3, 3>::Zero();
256  D_pos.diagonal() = admittance_state.damping.block<3, 1>(0, 0);
257  D_rot.diagonal() = admittance_state.damping.block<3, 1>(3, 0);
258  D_pos = rot_base_control * D_pos * rot_base_control.transpose();
259  D_rot = rot_base_control * D_rot * rot_base_control.transpose();
260  D.block<3, 3>(0, 0) = D_pos;
261  D.block<3, 3>(3, 3) = D_rot;
262 
263  // calculate admittance relative offset in base frame
264  Eigen::Isometry3d desired_trans_base_ft;
265  kinematics_->calculate_link_transform(
266  admittance_state.current_joint_pos, admittance_state.ft_sensor_frame, desired_trans_base_ft);
267  Eigen::Matrix<double, 6, 1> X;
268  X.block<3, 1>(0, 0) =
269  desired_trans_base_ft.translation() - admittance_state.ref_trans_base_ft.translation();
270  auto R_ref = admittance_state.ref_trans_base_ft.rotation();
271  auto R_desired = desired_trans_base_ft.rotation();
272  auto R = R_desired * R_ref.transpose();
273  auto angle_axis = Eigen::AngleAxisd(R);
274  X.block<3, 1>(3, 0) = angle_axis.angle() * angle_axis.axis();
275 
276  // get admittance relative velocity
277  auto X_dot = Eigen::Matrix<double, 6, 1>(admittance_state.admittance_velocity.data());
278 
279  // external force expressed in the base frame
280  auto F_base = admittance_state.wrench_base;
281 
282  // zero out any forces in the control frame
283  Eigen::Matrix<double, 6, 1> F_control;
284  F_control.block<3, 1>(0, 0) = rot_base_control.transpose() * F_base.block<3, 1>(0, 0);
285  F_control.block<3, 1>(3, 0) = rot_base_control.transpose() * F_base.block<3, 1>(3, 0);
286  F_control = F_control.cwiseProduct(admittance_state.selected_axes);
287  F_base.block<3, 1>(0, 0) = rot_base_control * F_control.block<3, 1>(0, 0);
288  F_base.block<3, 1>(3, 0) = rot_base_control * F_control.block<3, 1>(3, 0);
289 
290  // Compute admittance control law in the base frame: F = M*x_ddot + D*x_dot + K*x
291  Eigen::Matrix<double, 6, 1> X_ddot =
292  admittance_state.mass_inv.cwiseProduct(F_base - D * X_dot - K * X);
293  bool success = kinematics_->convert_cartesian_deltas_to_joint_deltas(
294  admittance_state.current_joint_pos, X_ddot, admittance_state.ft_sensor_frame,
295  admittance_state.joint_acc);
296 
297  // add damping if cartesian velocity falls below threshold
298  for (int64_t i = 0; i < admittance_state.joint_acc.size(); ++i)
299  {
300  admittance_state.joint_acc[i] -=
301  parameters_.admittance.joint_damping * admittance_state.joint_vel[i];
302  }
303 
304  // integrate motion in joint space
305  admittance_state.joint_vel += (admittance_state.joint_acc) * dt;
306  admittance_state.joint_pos += admittance_state.joint_vel * dt;
307 
308  // calculate admittance velocity corresponding to joint velocity ("base_link" frame)
309  success &= kinematics_->convert_joint_deltas_to_cartesian_deltas(
310  admittance_state.current_joint_pos, admittance_state.joint_vel,
311  admittance_state.ft_sensor_frame, admittance_state.admittance_velocity);
312  success &= kinematics_->convert_joint_deltas_to_cartesian_deltas(
313  admittance_state.current_joint_pos, admittance_state.joint_acc,
314  admittance_state.ft_sensor_frame, admittance_state.admittance_acceleration);
315 
316  return success;
317 }
318 
320  const geometry_msgs::msg::Wrench & measured_wrench,
321  const Eigen::Matrix<double, 3, 3> & sensor_world_rot,
322  const Eigen::Matrix<double, 3, 3> & cog_world_rot)
323 {
324  Eigen::Matrix<double, 3, 2, Eigen::ColMajor> new_wrench;
325  new_wrench(0, 0) = measured_wrench.force.x;
326  new_wrench(1, 0) = measured_wrench.force.y;
327  new_wrench(2, 0) = measured_wrench.force.z;
328  new_wrench(0, 1) = measured_wrench.torque.x;
329  new_wrench(1, 1) = measured_wrench.torque.y;
330  new_wrench(2, 1) = measured_wrench.torque.z;
331 
332  // transform to world frame
333  Eigen::Matrix<double, 3, 2> new_wrench_base = sensor_world_rot * new_wrench;
334 
335  // apply gravity compensation
336  new_wrench_base(2, 0) -= end_effector_weight_[2];
337  new_wrench_base.block<3, 1>(0, 1) -= (cog_world_rot * cog_pos_).cross(end_effector_weight_);
338 
339  // apply smoothing filter
340  for (Eigen::Index i = 0; i < 6; ++i)
341  {
342  wrench_world_(i) = filters::exponentialSmoothing(
343  new_wrench_base(i), wrench_world_(i), parameters_.ft_sensor.filter_coefficient);
344  }
345 }
346 
347 const control_msgs::msg::AdmittanceControllerState & AdmittanceRule::get_controller_state()
348 {
349  for (size_t i = 0; i < NUM_CARTESIAN_DOF; ++i)
350  {
351  auto idx = static_cast<Eigen::Index>(i);
352  state_message_.stiffness.data[i] = admittance_state_.stiffness[idx];
353  state_message_.damping.data[i] = admittance_state_.damping[idx];
354  state_message_.selected_axes.data[i] = static_cast<bool>(admittance_state_.selected_axes[idx]);
355  state_message_.mass.data[i] = admittance_state_.mass[idx];
356  }
357 
358  for (size_t i = 0; i < parameters_.joints.size(); ++i)
359  {
360  auto idx = static_cast<Eigen::Index>(i);
361  state_message_.joint_state.name[i] = parameters_.joints[i];
362  state_message_.joint_state.position[i] = admittance_state_.joint_pos[idx];
363  state_message_.joint_state.velocity[i] = admittance_state_.joint_vel[idx];
364  state_message_.joint_state.effort[i] = admittance_state_.joint_acc[idx];
365  }
366 
367  state_message_.wrench_base.wrench.force.x = admittance_state_.wrench_base[0];
368  state_message_.wrench_base.wrench.force.y = admittance_state_.wrench_base[1];
369  state_message_.wrench_base.wrench.force.z = admittance_state_.wrench_base[2];
370  state_message_.wrench_base.wrench.torque.x = admittance_state_.wrench_base[3];
371  state_message_.wrench_base.wrench.torque.y = admittance_state_.wrench_base[4];
372  state_message_.wrench_base.wrench.torque.z = admittance_state_.wrench_base[5];
373 
374  state_message_.admittance_velocity.twist.linear.x = admittance_state_.admittance_velocity[0];
375  state_message_.admittance_velocity.twist.linear.y = admittance_state_.admittance_velocity[1];
376  state_message_.admittance_velocity.twist.linear.z = admittance_state_.admittance_velocity[2];
377  state_message_.admittance_velocity.twist.angular.x = admittance_state_.admittance_velocity[3];
378  state_message_.admittance_velocity.twist.angular.y = admittance_state_.admittance_velocity[4];
379  state_message_.admittance_velocity.twist.angular.z = admittance_state_.admittance_velocity[5];
380 
381  state_message_.admittance_acceleration.twist.linear.x =
382  admittance_state_.admittance_acceleration[0];
383  state_message_.admittance_acceleration.twist.linear.y =
384  admittance_state_.admittance_acceleration[1];
385  state_message_.admittance_acceleration.twist.linear.z =
386  admittance_state_.admittance_acceleration[2];
387  state_message_.admittance_acceleration.twist.angular.x =
388  admittance_state_.admittance_acceleration[3];
389  state_message_.admittance_acceleration.twist.angular.y =
390  admittance_state_.admittance_acceleration[4];
391  state_message_.admittance_acceleration.twist.angular.z =
392  admittance_state_.admittance_acceleration[5];
393 
394  state_message_.admittance_position = tf2::eigenToTransform(admittance_state_.admittance_position);
395 
396  state_message_.ref_trans_base_ft.header.frame_id = parameters_.kinematics.base;
397  state_message_.ref_trans_base_ft.header.frame_id = "ft_reference";
398  state_message_.ref_trans_base_ft = tf2::eigenToTransform(admittance_state_.ref_trans_base_ft);
399 
400  Eigen::Quaterniond quat(admittance_state_.rot_base_control);
401  state_message_.rot_base_control.w = quat.w();
402  state_message_.rot_base_control.x = quat.x();
403  state_message_.rot_base_control.y = quat.y();
404  state_message_.rot_base_control.z = quat.z();
405 
406  state_message_.ft_sensor_frame.data =
407  admittance_state_.ft_sensor_frame; // TODO(anyone) remove dynamic allocation here
408 
409  return state_message_;
410 }
411 
412 template <typename T1, typename T2>
413 void AdmittanceRule::vec_to_eigen(const std::vector<T1> & data, T2 & matrix)
414 {
415  for (auto col = 0; col < matrix.cols(); col++)
416  {
417  for (auto row = 0; row < matrix.rows(); row++)
418  {
419  matrix(row, col) = data[static_cast<size_t>(row + col * matrix.rows())];
420  }
421  }
422 }
423 
424 } // namespace admittance_controller
425 
426 #endif // ADMITTANCE_CONTROLLER__ADMITTANCE_RULE_IMPL_HPP_
bool calculate_admittance_rule(AdmittanceState &admittance_state, double dt)
Definition: admittance_rule_impl.hpp:233
bool get_all_transforms(const trajectory_msgs::msg::JointTrajectoryPoint &current_joint_state, const trajectory_msgs::msg::JointTrajectoryPoint &reference_joint_state)
Definition: admittance_rule_impl.hpp:147
controller_interface::return_type reset(const size_t num_joints)
Reset all values back to default.
Definition: admittance_rule_impl.hpp:87
controller_interface::return_type configure(const std::shared_ptr< rclcpp_lifecycle::LifecycleNode > &node, const size_t num_joint, const std::string &robot_description)
Configure admittance rule memory using number of joints.
Definition: admittance_rule_impl.hpp:37
void apply_parameters_update()
Definition: admittance_rule_impl.hpp:124
const control_msgs::msg::AdmittanceControllerState & get_controller_state()
Definition: admittance_rule_impl.hpp:347
controller_interface::return_type update(const trajectory_msgs::msg::JointTrajectoryPoint &current_joint_state, const geometry_msgs::msg::Wrench &measured_wrench, const trajectory_msgs::msg::JointTrajectoryPoint &reference_joint_state, const rclcpp::Duration &period, trajectory_msgs::msg::JointTrajectoryPoint &desired_joint_states)
Definition: admittance_rule_impl.hpp:175
void process_wrench_measurements(const geometry_msgs::msg::Wrench &measured_wrench, const Eigen::Matrix< double, 3, 3 > &sensor_world_rot, const Eigen::Matrix< double, 3, 3 > &cog_world_rot)
Definition: admittance_rule_impl.hpp:319
Definition: admittance_controller.hpp:40
Definition: admittance_rule.hpp:56
Definition: admittance_rule.hpp:36