ros2_control - humble
Loading...
Searching...
No Matches
admittance_rule.hpp
1// Copyright (c) 2021, 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_HPP_
18#define ADMITTANCE_CONTROLLER__ADMITTANCE_RULE_HPP_
19
20#include <Eigen/Core>
21#include <Eigen/Geometry>
22#include <map>
23#include <memory>
24#include <string>
25#include <vector>
26
27#include "admittance_controller/admittance_controller_parameters.hpp"
28#include "control_msgs/msg/admittance_controller_state.hpp"
29#include "control_toolbox/filters.hpp"
30#include "controller_interface/controller_interface.hpp"
31#include "geometry_msgs/msg/wrench_stamped.hpp"
32#include "kinematics_interface/kinematics_interface.hpp"
33#include "pluginlib/class_loader.hpp"
34#include "tf2_eigen/tf2_eigen.hpp"
35#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
36#include "tf2_kdl/tf2_kdl.hpp"
37#include "tf2_ros/buffer.h"
38#include "tf2_ros/transform_listener.h"
39#include "trajectory_msgs/msg/joint_trajectory_point.hpp"
40
42{
44{
45 // transformation from force torque sensor frame to base link frame at reference joint angles
46 Eigen::Isometry3d ref_base_ft_;
47 // transformation from force torque sensor frame to base link frame at reference + admittance
48 // offset joint angles
49 Eigen::Isometry3d base_ft_;
50 // transformation from control frame to base link frame at reference + admittance offset joint
51 // angles
52 Eigen::Isometry3d base_control_;
53 // transformation from end effector frame to base link frame at reference + admittance offset
54 // joint angles
55 Eigen::Isometry3d base_tip_;
56 // transformation from center of gravity frame to base link frame at reference + admittance offset
57 // joint angles
58 Eigen::Isometry3d base_cog_;
59 // transformation from world frame to base link frame
60 Eigen::Isometry3d world_base_;
61};
62
64{
65 explicit AdmittanceState(size_t num_joints)
66 {
67 admittance_velocity.setZero();
68 admittance_acceleration.setZero();
69 damping.setZero();
70 mass.setOnes();
71 mass_inv.setZero();
72 stiffness.setZero();
73 selected_axes.setZero();
74 auto idx = static_cast<Eigen::Index>(num_joints);
75 current_joint_pos = Eigen::VectorXd::Zero(idx);
76 joint_pos = Eigen::VectorXd::Zero(idx);
77 joint_vel = Eigen::VectorXd::Zero(idx);
78 joint_acc = Eigen::VectorXd::Zero(idx);
79 }
80
81 Eigen::VectorXd current_joint_pos;
82 Eigen::VectorXd joint_pos;
83 Eigen::VectorXd joint_vel;
84 Eigen::VectorXd joint_acc;
85 Eigen::Matrix<double, 6, 1> damping;
86 Eigen::Matrix<double, 6, 1> mass;
87 Eigen::Matrix<double, 6, 1> mass_inv;
88 Eigen::Matrix<double, 6, 1> selected_axes;
89 Eigen::Matrix<double, 6, 1> stiffness;
90 Eigen::Matrix<double, 6, 1> wrench_base;
91 Eigen::Matrix<double, 6, 1> admittance_acceleration;
92 Eigen::Matrix<double, 6, 1> admittance_velocity;
93 Eigen::Isometry3d admittance_position;
94 Eigen::Matrix<double, 3, 3> rot_base_control;
95 Eigen::Isometry3d ref_trans_base_ft;
96 std::string ft_sensor_frame;
97};
98
100{
101public:
102 explicit AdmittanceRule(
103 const std::shared_ptr<admittance_controller::ParamListener> & parameter_handler)
104 {
105 parameter_handler_ = parameter_handler;
106 parameters_ = parameter_handler_->get_params();
107 num_joints_ = parameters_.joints.size();
108 admittance_state_ = AdmittanceState(num_joints_);
109 reset(num_joints_);
110 }
111
113 controller_interface::return_type configure(
114 const std::shared_ptr<rclcpp_lifecycle::LifecycleNode> & node, const size_t num_joint);
115
117 controller_interface::return_type reset(const size_t num_joints);
118
127 const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state,
128 const trajectory_msgs::msg::JointTrajectoryPoint & reference_joint_state);
129
136
148 controller_interface::return_type update(
149 const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state,
150 const geometry_msgs::msg::Wrench & measured_wrench,
151 const trajectory_msgs::msg::JointTrajectoryPoint & reference_joint_state,
152 const rclcpp::Duration & period,
153 trajectory_msgs::msg::JointTrajectoryPoint & desired_joint_states);
154
161 const control_msgs::msg::AdmittanceControllerState & get_controller_state();
162
163public:
164 // admittance config parameters
165 std::shared_ptr<admittance_controller::ParamListener> parameter_handler_;
166 admittance_controller::Params parameters_;
167
168protected:
176 bool calculate_admittance_rule(AdmittanceState & admittance_state, double dt);
177
187 const geometry_msgs::msg::Wrench & measured_wrench,
188 const Eigen::Matrix<double, 3, 3> & sensor_world_rot,
189 const Eigen::Matrix<double, 3, 3> & cog_world_rot);
190
191 template <typename T1, typename T2>
192 void vec_to_eigen(const std::vector<T1> & data, T2 & matrix);
193
194 // number of robot joint
195 size_t num_joints_;
196
197 // Kinematics interface plugin loader
198 std::shared_ptr<pluginlib::ClassLoader<kinematics_interface::KinematicsInterface>>
199 kinematics_loader_;
200 std::unique_ptr<kinematics_interface::KinematicsInterface> kinematics_;
201
202 // filtered wrench in world frame
203 Eigen::Matrix<double, 6, 1> wrench_world_;
204
205 // admittance controllers internal state
206 AdmittanceState admittance_state_{0};
207
208 // transforms needed for admittance update
209 AdmittanceTransforms admittance_transforms_;
210
211 // position of center of gravity in cog_frame
212 Eigen::Vector3d cog_pos_;
213
214 // force applied to sensor due to weight of end effector
215 Eigen::Vector3d end_effector_weight_;
216
217 // ROS
218 control_msgs::msg::AdmittanceControllerState state_message_;
219};
220
221} // namespace admittance_controller
222
223#endif // ADMITTANCE_CONTROLLER__ADMITTANCE_RULE_HPP_
Definition admittance_rule.hpp:100
bool calculate_admittance_rule(AdmittanceState &admittance_state, double dt)
Definition admittance_rule_impl.hpp:230
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:84
void apply_parameters_update()
Definition admittance_rule_impl.hpp:121
const control_msgs::msg::AdmittanceControllerState & get_controller_state()
Definition admittance_rule_impl.hpp:344
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: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:316
Definition admittance_controller.hpp:48
Definition admittance_rule.hpp:64
Definition admittance_rule.hpp:44