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