ros2_control - rolling
kinematics_interface.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 //
17 
18 #ifndef KINEMATICS_INTERFACE__KINEMATICS_INTERFACE_HPP_
19 #define KINEMATICS_INTERFACE__KINEMATICS_INTERFACE_HPP_
20 
21 #include <memory>
22 #include <string>
23 #include <vector>
24 
25 #include "eigen3/Eigen/Core"
26 #include "eigen3/Eigen/Geometry"
27 #include "eigen3/Eigen/LU"
28 #include "rclcpp/logging.hpp"
29 #include "rclcpp/node_interfaces/node_parameters_interface.hpp"
30 
32 {
34 {
35 public:
36  KinematicsInterface() = default;
37 
38  virtual ~KinematicsInterface() = default;
39 
43  virtual bool initialize(
44  std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface> parameters_interface,
45  const std::string & end_effector_name) = 0;
46 
56  const Eigen::VectorXd & joint_pos, const Eigen::Matrix<double, 6, 1> & delta_x,
57  const std::string & link_name, Eigen::VectorXd & delta_theta) = 0;
58 
68  const Eigen::VectorXd & joint_pos, const Eigen::VectorXd & delta_theta,
69  const std::string & link_name, Eigen::Matrix<double, 6, 1> & delta_x) = 0;
70 
79  const Eigen::VectorXd & joint_pos, const std::string & link_name,
80  Eigen::Isometry3d & transform) = 0;
81 
89  virtual bool calculate_jacobian(
90  const Eigen::VectorXd & joint_pos, const std::string & link_name,
91  Eigen::Matrix<double, 6, Eigen::Dynamic> & jacobian) = 0;
92 
94  std::vector<double> & joint_pos_vec, const std::vector<double> & delta_x_vec,
95  const std::string & link_name, std::vector<double> & delta_theta_vec);
96 
98  const std::vector<double> & joint_pos_vec, const std::vector<double> & delta_theta_vec,
99  const std::string & link_name, std::vector<double> & delta_x_vec);
100 
102  const std::vector<double> & joint_pos_vec, const std::string & link_name,
103  Eigen::Isometry3d & transform);
104 
105  bool calculate_jacobian(
106  const std::vector<double> & joint_pos_vec, const std::string & link_name,
107  Eigen::Matrix<double, 6, Eigen::Dynamic> & jacobian);
108 };
109 
110 } // namespace kinematics_interface
111 
112 #endif // KINEMATICS_INTERFACE__KINEMATICS_INTERFACE_HPP_
Definition: kinematics_interface.hpp:34
virtual bool initialize(std::shared_ptr< rclcpp::node_interfaces::NodeParametersInterface > parameters_interface, const std::string &end_effector_name)=0
Initialize plugin. This method must be called before any other.
virtual bool convert_joint_deltas_to_cartesian_deltas(const Eigen::VectorXd &joint_pos, const Eigen::VectorXd &delta_theta, const std::string &link_name, Eigen::Matrix< double, 6, 1 > &delta_x)=0
Convert joint delta-theta to Cartesian delta-x.
virtual bool convert_cartesian_deltas_to_joint_deltas(const Eigen::VectorXd &joint_pos, const Eigen::Matrix< double, 6, 1 > &delta_x, const std::string &link_name, Eigen::VectorXd &delta_theta)=0
Convert Cartesian delta-x to joint delta-theta, using the Jacobian.
virtual bool calculate_jacobian(const Eigen::VectorXd &joint_pos, const std::string &link_name, Eigen::Matrix< double, 6, Eigen::Dynamic > &jacobian)=0
Calculates the jacobian for a specified link using provided joint positions.
virtual bool calculate_link_transform(const Eigen::VectorXd &joint_pos, const std::string &link_name, Eigen::Isometry3d &transform)=0
Calculates the joint transform for a specified link using provided joint positions.
Definition: kinematics_interface.hpp:32