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