ros2_control - rolling
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
22#include <memory>
23#include <string>
24#include <vector>
25
26#include "admittance_controller/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
34{
36{
37 explicit AdmittanceState(size_t num_joints)
38 {
39 admittance_velocity.setZero();
40 admittance_acceleration.setZero();
41 damping.setZero();
42 mass.setOnes();
43 mass_inv.setZero();
44 stiffness.setZero();
45 selected_axes.setZero();
46 auto idx = static_cast<Eigen::Index>(num_joints);
47 current_joint_pos = Eigen::VectorXd::Zero(idx);
48 joint_pos = Eigen::VectorXd::Zero(idx);
49 joint_vel = Eigen::VectorXd::Zero(idx);
50 joint_acc = Eigen::VectorXd::Zero(idx);
51 }
52
53 Eigen::VectorXd current_joint_pos;
54 Eigen::VectorXd joint_pos;
55 Eigen::VectorXd joint_vel;
56 Eigen::VectorXd joint_acc;
57 Eigen::Matrix<double, 6, 1> damping;
58 Eigen::Matrix<double, 6, 1> mass;
59 Eigen::Matrix<double, 6, 1> mass_inv;
60 Eigen::Matrix<double, 6, 1> selected_axes;
61 Eigen::Matrix<double, 6, 1> stiffness;
62 Eigen::Matrix<double, 6, 1> wrench_base;
63 Eigen::Matrix<double, 6, 1> admittance_acceleration;
64 Eigen::Matrix<double, 6, 1> admittance_velocity;
65 Eigen::Isometry3d admittance_position;
66 Eigen::Matrix<double, 3, 3> rot_base_control;
67 Eigen::Isometry3d ref_trans_base_ft;
68 std::string ft_sensor_frame;
69};
70
72{
73public:
74 explicit AdmittanceRule(
75 const std::shared_ptr<admittance_controller::ParamListener> & parameter_handler)
76 {
77 parameter_handler_ = parameter_handler;
78 parameters_ = parameter_handler_->get_params();
79 num_joints_ = parameters_.joints.size();
80 admittance_state_ = AdmittanceState(num_joints_);
81 reset(num_joints_);
82 }
83
85 controller_interface::return_type configure(
86 const std::shared_ptr<rclcpp_lifecycle::LifecycleNode> & node, const size_t num_joint,
87 const std::string & robot_description);
88
90 controller_interface::return_type reset(const size_t num_joints);
91
98
114 controller_interface::return_type update(
115 const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_state,
116 const geometry_msgs::msg::Wrench & measured_wrench,
117 const trajectory_msgs::msg::JointTrajectoryPoint & reference_joint_state,
118 const rclcpp::Duration & period,
119 trajectory_msgs::msg::JointTrajectoryPoint & desired_joint_states);
120
127 const control_msgs::msg::AdmittanceControllerState & get_controller_state();
128
129public:
130 // admittance config parameters
131 std::shared_ptr<admittance_controller::ParamListener> parameter_handler_;
132 admittance_controller::Params parameters_;
133
134protected:
142 bool calculate_admittance_rule(AdmittanceState & admittance_state, double dt);
143
153 const geometry_msgs::msg::Wrench & measured_wrench,
154 const Eigen::Matrix<double, 3, 3> & sensor_world_rot,
155 const Eigen::Matrix<double, 3, 3> & cog_world_rot);
156
157 template <typename T1, typename T2>
158 void vec_to_eigen(const std::vector<T1> & data, T2 & matrix);
159
160 // number of robot joint
161 size_t num_joints_;
162
163 // Kinematics interface plugin loader
164 std::shared_ptr<pluginlib::ClassLoader<kinematics_interface::KinematicsInterface>>
165 kinematics_loader_;
166 std::unique_ptr<kinematics_interface::KinematicsInterface> kinematics_;
167
168 // filtered wrench in world frame
169 Eigen::Matrix<double, 6, 1> wrench_world_;
170
171 // admittance controllers internal state
172 AdmittanceState admittance_state_{0};
173
174 // position of center of gravity in cog_frame
175 Eigen::Vector3d cog_pos_;
176
177 // force applied to sensor due to weight of end effector
178 Eigen::Vector3d end_effector_weight_;
179
180 // ROS
181 control_msgs::msg::AdmittanceControllerState state_message_;
182};
183
184} // namespace admittance_controller
185
186#endif // ADMITTANCE_CONTROLLER__ADMITTANCE_RULE_HPP_
Definition admittance_rule.hpp:72
bool calculate_admittance_rule(AdmittanceState &admittance_state, double dt)
Definition admittance_rule_impl.hpp:223
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:119
const control_msgs::msg::AdmittanceControllerState & get_controller_state()
Definition admittance_rule_impl.hpp:337
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:141
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:309
Definition admittance_controller.hpp:39
Definition admittance_rule.hpp:36