ros2_control - rolling
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 
22 #include <memory>
23 #include <string>
24 #include <vector>
25 
26 #include "admittance_controller_parameters.hpp"
27 #include "control_msgs/msg/admittance_controller_state.hpp"
28 #include "controller_interface/controller_interface_base.hpp"
29 #include "kinematics_interface/kinematics_interface.hpp"
30 #include "pluginlib/class_loader.hpp"
31 #include "trajectory_msgs/msg/joint_trajectory_point.hpp"
32 
33 namespace admittance_controller
34 {
36 {
37  // transformation from force torque sensor frame to base link frame at reference joint angles
38  Eigen::Isometry3d ref_base_ft_;
39  // transformation from force torque sensor frame to base link frame at reference + admittance
40  // offset joint angles
41  Eigen::Isometry3d base_ft_;
42  // transformation from control frame to base link frame at reference + admittance offset joint
43  // angles
44  Eigen::Isometry3d base_control_;
45  // transformation from end effector frame to base link frame at reference + admittance offset
46  // joint angles
47  Eigen::Isometry3d base_tip_;
48  // transformation from center of gravity frame to base link frame at reference + admittance offset
49  // joint angles
50  Eigen::Isometry3d base_cog_;
51  // transformation from world frame to base link frame
52  Eigen::Isometry3d world_base_;
53 };
54 
56 {
57  explicit AdmittanceState(size_t num_joints)
58  {
59  admittance_velocity.setZero();
60  admittance_acceleration.setZero();
61  damping.setZero();
62  mass.setOnes();
63  mass_inv.setZero();
64  stiffness.setZero();
65  selected_axes.setZero();
66  auto idx = static_cast<Eigen::Index>(num_joints);
67  current_joint_pos = Eigen::VectorXd::Zero(idx);
68  joint_pos = Eigen::VectorXd::Zero(idx);
69  joint_vel = Eigen::VectorXd::Zero(idx);
70  joint_acc = Eigen::VectorXd::Zero(idx);
71  }
72 
73  Eigen::VectorXd current_joint_pos;
74  Eigen::VectorXd joint_pos;
75  Eigen::VectorXd joint_vel;
76  Eigen::VectorXd joint_acc;
77  Eigen::Matrix<double, 6, 1> damping;
78  Eigen::Matrix<double, 6, 1> mass;
79  Eigen::Matrix<double, 6, 1> mass_inv;
80  Eigen::Matrix<double, 6, 1> selected_axes;
81  Eigen::Matrix<double, 6, 1> stiffness;
82  Eigen::Matrix<double, 6, 1> wrench_base;
83  Eigen::Matrix<double, 6, 1> admittance_acceleration;
84  Eigen::Matrix<double, 6, 1> admittance_velocity;
85  Eigen::Isometry3d admittance_position;
86  Eigen::Matrix<double, 3, 3> rot_base_control;
87  Eigen::Isometry3d ref_trans_base_ft;
88  std::string ft_sensor_frame;
89 };
90 
92 {
93 public:
94  explicit AdmittanceRule(
95  const std::shared_ptr<admittance_controller::ParamListener> & parameter_handler)
96  {
97  parameter_handler_ = parameter_handler;
98  parameters_ = parameter_handler_->get_params();
99  num_joints_ = parameters_.joints.size();
100  admittance_state_ = AdmittanceState(num_joints_);
101  reset(num_joints_);
102  }
103 
105  controller_interface::return_type configure(
106  const std::shared_ptr<rclcpp_lifecycle::LifecycleNode> & node, const size_t num_joint,
107  const std::string & robot_description);
108 
110  controller_interface::return_type reset(const size_t num_joints);
111 
119  bool get_all_transforms(
120  const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state,
121  const trajectory_msgs::msg::JointTrajectoryPoint & reference_joint_state);
122 
129 
141  controller_interface::return_type update(
142  const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state,
143  const geometry_msgs::msg::Wrench & measured_wrench,
144  const trajectory_msgs::msg::JointTrajectoryPoint & reference_joint_state,
145  const rclcpp::Duration & period,
146  trajectory_msgs::msg::JointTrajectoryPoint & desired_joint_states);
147 
154  const control_msgs::msg::AdmittanceControllerState & get_controller_state();
155 
156 public:
157  // admittance config parameters
158  std::shared_ptr<admittance_controller::ParamListener> parameter_handler_;
159  admittance_controller::Params parameters_;
160 
161 protected:
169  bool calculate_admittance_rule(AdmittanceState & admittance_state, double dt);
170 
180  const geometry_msgs::msg::Wrench & measured_wrench,
181  const Eigen::Matrix<double, 3, 3> & sensor_world_rot,
182  const Eigen::Matrix<double, 3, 3> & cog_world_rot);
183 
184  template <typename T1, typename T2>
185  void vec_to_eigen(const std::vector<T1> & data, T2 & matrix);
186 
187  // number of robot joint
188  size_t num_joints_;
189 
190  // Kinematics interface plugin loader
191  std::shared_ptr<pluginlib::ClassLoader<kinematics_interface::KinematicsInterface>>
192  kinematics_loader_;
193  std::unique_ptr<kinematics_interface::KinematicsInterface> kinematics_;
194 
195  // filtered wrench in world frame
196  Eigen::Matrix<double, 6, 1> wrench_world_;
197 
198  // admittance controllers internal state
199  AdmittanceState admittance_state_{0};
200 
201  // transforms needed for admittance update
202  AdmittanceTransforms admittance_transforms_;
203 
204  // position of center of gravity in cog_frame
205  Eigen::Vector3d cog_pos_;
206 
207  // force applied to sensor due to weight of end effector
208  Eigen::Vector3d end_effector_weight_;
209 
210  // ROS
211  control_msgs::msg::AdmittanceControllerState state_message_;
212 };
213 
214 } // namespace admittance_controller
215 
216 #endif // ADMITTANCE_CONTROLLER__ADMITTANCE_RULE_HPP_
Definition: admittance_rule.hpp:92
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