ros2_control - rolling
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 <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
32{
33
34constexpr auto NUM_CARTESIAN_DOF = 6; // (3 translation + 3 rotation)
35
37controller_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 // configure force torque sensor frame in state message
85 state_message_.ft_sensor_frame.data = parameters_.ft_sensor.frame.id;
86
87 return controller_interface::return_type::OK;
88}
89
90controller_interface::return_type AdmittanceRule::reset(const size_t num_joints)
91{
92 // reset state message fields
93 state_message_.joint_state.name.assign(num_joints, "");
94 state_message_.joint_state.position.assign(num_joints, 0);
95 state_message_.joint_state.velocity.assign(num_joints, 0);
96 state_message_.joint_state.effort.assign(num_joints, 0);
97 for (size_t i = 0; i < parameters_.joints.size(); ++i)
98 {
99 state_message_.joint_state.name = parameters_.joints;
100 }
101 state_message_.mass.data.resize(NUM_CARTESIAN_DOF, 0.0);
102 state_message_.selected_axes.data.resize(NUM_CARTESIAN_DOF, 0);
103 state_message_.damping.data.resize(NUM_CARTESIAN_DOF, 0);
104 state_message_.stiffness.data.resize(NUM_CARTESIAN_DOF, 0);
105 state_message_.wrench_base.header.frame_id = parameters_.kinematics.base;
106 state_message_.admittance_velocity.header.frame_id = parameters_.kinematics.base;
107 state_message_.admittance_acceleration.header.frame_id = parameters_.kinematics.base;
108
109 // reset admittance state
110 admittance_state_ = AdmittanceState(num_joints);
111
112 // reset forces
113 wrench_world_.setZero();
114 end_effector_weight_.setZero();
115
116 // load/initialize Eigen types from parameters
118
119 return controller_interface::return_type::OK;
120}
121
123{
124 parameter_handler_->try_get_params(parameters_);
125
126 // update param values
127 end_effector_weight_[2] = -parameters_.gravity_compensation.CoG.force;
128 vec_to_eigen(parameters_.gravity_compensation.CoG.pos, cog_pos_);
129 vec_to_eigen(parameters_.admittance.mass, admittance_state_.mass);
130 vec_to_eigen(parameters_.admittance.stiffness, admittance_state_.stiffness);
131 vec_to_eigen(parameters_.admittance.selected_axes, admittance_state_.selected_axes);
132
133 for (size_t i = 0; i < NUM_CARTESIAN_DOF; ++i)
134 {
135 auto idx = static_cast<Eigen::Index>(i);
136 admittance_state_.mass_inv[idx] = 1.0 / parameters_.admittance.mass[i];
137 admittance_state_.damping[idx] =
138 parameters_.admittance.damping_ratio[i] * 2 *
139 sqrt(admittance_state_.mass[idx] * admittance_state_.stiffness[idx]);
140 }
141}
142
143// Update from reference joint states
144controller_interface::return_type AdmittanceRule::update(
145 const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state,
146 const geometry_msgs::msg::Wrench & measured_wrench,
147 const trajectory_msgs::msg::JointTrajectoryPoint & reference_joint_state,
148 const rclcpp::Duration & period, trajectory_msgs::msg::JointTrajectoryPoint & desired_joint_state)
149{
150 // duration & live-parameter refresh
151 const double dt = period.seconds();
152
153 if (parameters_.enable_parameter_update_without_reactivation)
154 {
156 }
157
158 bool success = true;
159
160 // Reusable transform variable
161 Eigen::Isometry3d tf;
162
163 // --- FT sensor frame to base frame (translation + rotation) ---
164 success &= kinematics_->calculate_link_transform(
165 reference_joint_state.positions, parameters_.ft_sensor.frame.id, tf);
166 admittance_state_.ref_trans_base_ft = tf;
167
168 // --- world frame to base frame (we only need the rotation) ---
169 success &= kinematics_->calculate_link_transform(
170 current_joint_state.positions, parameters_.fixed_world_frame.frame.id, tf);
171 const Eigen::Matrix3d rot_world_base = tf.rotation();
172
173 // --- control/base frame to base frame (rotation only) ---
174 success &= kinematics_->calculate_link_transform(
175 current_joint_state.positions, parameters_.control.frame.id, tf);
176 admittance_state_.rot_base_control = tf.rotation();
177
178 success &= kinematics_->calculate_link_transform(
179 current_joint_state.positions, parameters_.gravity_compensation.frame.id, tf);
180 const Eigen::Matrix3d rot_tf_cog = tf.rotation();
181
182 success &= kinematics_->calculate_link_transform(
183 current_joint_state.positions, parameters_.ft_sensor.frame.id, tf);
184 const Eigen::Matrix3d rot_tf_base_ft = tf.rotation();
185
186 // wrench processing (gravity + filter) in world
188 measured_wrench,
189 // pass rotations into sensor and CoG:
190 rot_world_base * rot_tf_base_ft, rot_world_base * rot_tf_cog);
191
192 // transform filtered wrench into the robot base frame
193 admittance_state_.wrench_base.block<3, 1>(0, 0) =
194 rot_world_base.transpose() * wrench_world_.block<3, 1>(0, 0);
195 admittance_state_.wrench_base.block<3, 1>(3, 0) =
196 rot_world_base.transpose() * wrench_world_.block<3, 1>(3, 0);
197
198 // populate current joint positions in the state
199 vec_to_eigen(current_joint_state.positions, admittance_state_.current_joint_pos);
200
201 admittance_state_.ft_sensor_frame = parameters_.ft_sensor.frame.id;
202
203 // compute admittance dynamics
204 success &= calculate_admittance_rule(admittance_state_, dt);
205 if (!success)
206 {
207 desired_joint_state = reference_joint_state;
208 return controller_interface::return_type::ERROR;
209 }
210
211 // Update final desired_joint_state using the computed transforms
212 for (size_t i = 0; i < num_joints_; ++i)
213 {
214 auto idx = static_cast<Eigen::Index>(i);
215 desired_joint_state.positions[i] =
216 reference_joint_state.positions[i] + admittance_state_.joint_pos[idx];
217 desired_joint_state.velocities[i] =
218 reference_joint_state.velocities[i] + admittance_state_.joint_vel[idx];
219 desired_joint_state.accelerations[i] =
220 reference_joint_state.accelerations[i] + admittance_state_.joint_acc[idx];
221 }
222
223 return controller_interface::return_type::OK;
224}
225
227{
228 // Create stiffness matrix in base frame. The user-provided values of admittance_state.stiffness
229 // correspond to the six diagonal elements of the stiffness matrix expressed in the control frame
230 auto rot_base_control = admittance_state.rot_base_control;
231 Eigen::Matrix<double, 6, 6> rot_base_control_6d = Eigen::Matrix<double, 6, 6>::Zero();
232 rot_base_control_6d.topLeftCorner<3, 3>() = rot_base_control;
233 rot_base_control_6d.bottomRightCorner<3, 3>() = rot_base_control;
234 Eigen::Matrix<double, 6, 6> K = Eigen::Matrix<double, 6, 6>::Zero();
235 K.block<3, 3>(0, 0).diagonal() = admittance_state.stiffness.block<3, 1>(0, 0);
236 K.block<3, 3>(3, 3).diagonal() = admittance_state.stiffness.block<3, 1>(3, 0);
237
238 // The same for damping
239 Eigen::Matrix<double, 6, 6> D = Eigen::Matrix<double, 6, 6>::Zero();
240 D.block<3, 3>(0, 0).diagonal() = admittance_state.damping.block<3, 1>(0, 0);
241 D.block<3, 3>(3, 3).diagonal() = admittance_state.damping.block<3, 1>(3, 0);
242
243 // The same for mass
244 Eigen::Matrix<double, 6, 6> M_inv = Eigen::Matrix<double, 6, 6>::Zero();
245 M_inv.block<3, 3>(0, 0).diagonal() = admittance_state.mass_inv.block<3, 1>(0, 0);
246 M_inv.block<3, 3>(3, 3).diagonal() = admittance_state.mass_inv.block<3, 1>(3, 0);
247
248 // calculate admittance relative offset in base frame
249 Eigen::Isometry3d desired_trans_base_ft;
250 kinematics_->calculate_link_transform(
251 admittance_state.current_joint_pos, admittance_state.ft_sensor_frame, desired_trans_base_ft);
252 Eigen::Matrix<double, 6, 1> X;
253 X.block<3, 1>(0, 0) =
254 desired_trans_base_ft.translation() - admittance_state.ref_trans_base_ft.translation();
255 auto R_ref = admittance_state.ref_trans_base_ft.rotation();
256 auto R_desired = desired_trans_base_ft.rotation();
257 auto R = R_desired * R_ref.transpose();
258 auto angle_axis = Eigen::AngleAxisd(R);
259 X.block<3, 1>(3, 0) = angle_axis.angle() * angle_axis.axis();
260
261 // get admittance relative velocity
262 auto X_dot = Eigen::Matrix<double, 6, 1>(admittance_state.admittance_velocity.data());
263
264 // external force expressed in the base frame
265 auto F_base = admittance_state.wrench_base;
266
267 // zero out any forces in the control frame
268 Eigen::Matrix<double, 6, 1> F_control = rot_base_control_6d.transpose() * F_base;
269 F_control = F_control.cwiseProduct(admittance_state.selected_axes);
270
271 // Compute admittance control law in the base frame:
272 // F_control = M*R^T*x_ddot + D*R^T*x_dot + K*R^T*x,
273 // with R being the rotation matrix from base to control frame
274 Eigen::Matrix<double, 6, 1> X_ddot = rot_base_control_6d * M_inv *
275 (F_control - D * rot_base_control_6d.transpose() * X_dot -
276 K * rot_base_control_6d.transpose() * X);
277 bool success = kinematics_->convert_cartesian_deltas_to_joint_deltas(
278 admittance_state.current_joint_pos, X_ddot, admittance_state.ft_sensor_frame,
279 admittance_state.joint_acc);
280
281 // add damping if cartesian velocity falls below threshold
282 for (int64_t i = 0; i < admittance_state.joint_acc.size(); ++i)
283 {
284 admittance_state.joint_acc[i] -=
285 parameters_.admittance.joint_damping * admittance_state.joint_vel[i];
286 }
287
288 // integrate motion in joint space
289 admittance_state.joint_vel += (admittance_state.joint_acc) * dt;
290 admittance_state.joint_pos += admittance_state.joint_vel * dt;
291
292 // calculate admittance velocity corresponding to joint velocity ("base_link" frame)
293 success &= kinematics_->convert_joint_deltas_to_cartesian_deltas(
294 admittance_state.current_joint_pos, admittance_state.joint_vel,
295 admittance_state.ft_sensor_frame, admittance_state.admittance_velocity);
296 success &= kinematics_->convert_joint_deltas_to_cartesian_deltas(
297 admittance_state.current_joint_pos, admittance_state.joint_acc,
298 admittance_state.ft_sensor_frame, admittance_state.admittance_acceleration);
299
300 return success;
301}
302
304 const geometry_msgs::msg::Wrench & measured_wrench,
305 const Eigen::Matrix<double, 3, 3> & sensor_world_rot,
306 const Eigen::Matrix<double, 3, 3> & cog_world_rot)
307{
308 Eigen::Matrix<double, 3, 2, Eigen::ColMajor> new_wrench;
309 new_wrench(0, 0) = measured_wrench.force.x;
310 new_wrench(1, 0) = measured_wrench.force.y;
311 new_wrench(2, 0) = measured_wrench.force.z;
312 new_wrench(0, 1) = measured_wrench.torque.x;
313 new_wrench(1, 1) = measured_wrench.torque.y;
314 new_wrench(2, 1) = measured_wrench.torque.z;
315
316 // transform to world frame
317 Eigen::Matrix<double, 3, 2> new_wrench_base = sensor_world_rot * new_wrench;
318
319 // apply gravity compensation
320 new_wrench_base(2, 0) -= end_effector_weight_[2];
321 new_wrench_base.block<3, 1>(0, 1) -= (cog_world_rot * cog_pos_).cross(end_effector_weight_);
322
323 // apply smoothing filter
324 for (Eigen::Index i = 0; i < 6; ++i)
325 {
326 wrench_world_(i) = filters::exponentialSmoothing(
327 new_wrench_base(i), wrench_world_(i), parameters_.ft_sensor.filter_coefficient);
328 }
329}
330
331const control_msgs::msg::AdmittanceControllerState & AdmittanceRule::get_controller_state()
332{
333 for (size_t i = 0; i < NUM_CARTESIAN_DOF; ++i)
334 {
335 auto idx = static_cast<Eigen::Index>(i);
336 state_message_.stiffness.data[i] = admittance_state_.stiffness[idx];
337 state_message_.damping.data[i] = admittance_state_.damping[idx];
338 state_message_.selected_axes.data[i] = static_cast<bool>(admittance_state_.selected_axes[idx]);
339 state_message_.mass.data[i] = admittance_state_.mass[idx];
340 }
341
342 for (size_t i = 0; i < parameters_.joints.size(); ++i)
343 {
344 auto idx = static_cast<Eigen::Index>(i);
345 state_message_.joint_state.name[i] = parameters_.joints[i];
346 state_message_.joint_state.position[i] = admittance_state_.joint_pos[idx];
347 state_message_.joint_state.velocity[i] = admittance_state_.joint_vel[idx];
348 state_message_.joint_state.effort[i] = admittance_state_.joint_acc[idx];
349 }
350
351 state_message_.wrench_base.wrench.force.x = admittance_state_.wrench_base[0];
352 state_message_.wrench_base.wrench.force.y = admittance_state_.wrench_base[1];
353 state_message_.wrench_base.wrench.force.z = admittance_state_.wrench_base[2];
354 state_message_.wrench_base.wrench.torque.x = admittance_state_.wrench_base[3];
355 state_message_.wrench_base.wrench.torque.y = admittance_state_.wrench_base[4];
356 state_message_.wrench_base.wrench.torque.z = admittance_state_.wrench_base[5];
357
358 state_message_.admittance_velocity.twist.linear.x = admittance_state_.admittance_velocity[0];
359 state_message_.admittance_velocity.twist.linear.y = admittance_state_.admittance_velocity[1];
360 state_message_.admittance_velocity.twist.linear.z = admittance_state_.admittance_velocity[2];
361 state_message_.admittance_velocity.twist.angular.x = admittance_state_.admittance_velocity[3];
362 state_message_.admittance_velocity.twist.angular.y = admittance_state_.admittance_velocity[4];
363 state_message_.admittance_velocity.twist.angular.z = admittance_state_.admittance_velocity[5];
364
365 state_message_.admittance_acceleration.twist.linear.x =
366 admittance_state_.admittance_acceleration[0];
367 state_message_.admittance_acceleration.twist.linear.y =
368 admittance_state_.admittance_acceleration[1];
369 state_message_.admittance_acceleration.twist.linear.z =
370 admittance_state_.admittance_acceleration[2];
371 state_message_.admittance_acceleration.twist.angular.x =
372 admittance_state_.admittance_acceleration[3];
373 state_message_.admittance_acceleration.twist.angular.y =
374 admittance_state_.admittance_acceleration[4];
375 state_message_.admittance_acceleration.twist.angular.z =
376 admittance_state_.admittance_acceleration[5];
377
378 state_message_.admittance_position = tf2::eigenToTransform(admittance_state_.admittance_position);
379 state_message_.admittance_position.header.frame_id = parameters_.kinematics.base;
380 state_message_.admittance_position.child_frame_id = "admittance_offset";
381
382 state_message_.ref_trans_base_ft = tf2::eigenToTransform(admittance_state_.ref_trans_base_ft);
383 state_message_.ref_trans_base_ft.header.frame_id = parameters_.kinematics.base;
384 state_message_.ref_trans_base_ft.child_frame_id = parameters_.ft_sensor.frame.id;
385
386 Eigen::Quaterniond quat(admittance_state_.rot_base_control);
387 state_message_.rot_base_control.w = quat.w();
388 state_message_.rot_base_control.x = quat.x();
389 state_message_.rot_base_control.y = quat.y();
390 state_message_.rot_base_control.z = quat.z();
391
392 return state_message_;
393}
394
395template <typename T1, typename T2>
396void AdmittanceRule::vec_to_eigen(const std::vector<T1> & data, T2 & matrix)
397{
398 for (auto col = 0; col < matrix.cols(); col++)
399 {
400 for (auto row = 0; row < matrix.rows(); row++)
401 {
402 matrix(row, col) = data[static_cast<size_t>(row + col * matrix.rows())];
403 }
404 }
405}
406
407} // namespace admittance_controller
408
409#endif // ADMITTANCE_CONTROLLER__ADMITTANCE_RULE_IMPL_HPP_
bool calculate_admittance_rule(AdmittanceState &admittance_state, double dt)
Definition admittance_rule_impl.hpp:226
controller_interface::return_type reset(const size_t num_joints)
Reset all values back to default.
Definition admittance_rule_impl.hpp:90
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:122
const control_msgs::msg::AdmittanceControllerState & get_controller_state()
Definition admittance_rule_impl.hpp:331
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:144
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:303
Definition admittance_controller.hpp:39
Definition admittance_rule.hpp:36