ros2_control - rolling
Loading...
Searching...
No Matches
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 <Eigen/Core>
22#include <Eigen/Geometry>
23#include <Eigen/LU>
24
25#include <memory>
26#include <string>
27#include <vector>
28
29#include "rclcpp/logging.hpp"
30#include "rclcpp/node_interfaces/node_parameters_interface.hpp"
31
32// TODO(anyone): Use std::source_location::function_name() once we require C++20
33#ifdef _MSC_VER
34#define FUNCTION_SIGNATURE __FUNCSIG__
35#else
36#define FUNCTION_SIGNATURE __PRETTY_FUNCTION__
37#endif
38
40{
41
42using Vector6d = Eigen::Matrix<double, 6, 1>;
43
45{
46public:
47 KinematicsInterface() = default;
48
49 virtual ~KinematicsInterface() = default;
50
58 virtual bool initialize(
59 const std::string & robot_description,
60 std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface> parameters_interface,
61 const std::string & param_namespace) = 0;
62
72 const Eigen::VectorXd & joint_pos, const Eigen::Matrix<double, 6, 1> & delta_x,
73 const std::string & link_name, Eigen::VectorXd & delta_theta) = 0;
74
84 const Eigen::VectorXd & joint_pos, const Eigen::VectorXd & delta_theta,
85 const std::string & link_name, Eigen::Matrix<double, 6, 1> & delta_x) = 0;
86
95 const Eigen::VectorXd & joint_pos, const std::string & link_name,
96 Eigen::Isometry3d & transform) = 0;
97
105 virtual bool calculate_jacobian(
106 const Eigen::VectorXd & joint_pos, const std::string & link_name,
107 Eigen::Matrix<double, 6, Eigen::Dynamic> & jacobian) = 0;
108
117 const Eigen::VectorXd & joint_pos, const std::string & link_name,
118 Eigen::Matrix<double, Eigen::Dynamic, 6> & jacobian_inverse) = 0;
119
129 Eigen::Matrix<double, 7, 1> & x_a, Eigen::Matrix<double, 7, 1> & x_b, double dt,
130 Eigen::Matrix<double, 6, 1> & delta_x) = 0;
131
133 std::vector<double> & joint_pos_vec, const std::vector<double> & delta_x_vec,
134 const std::string & link_name, std::vector<double> & delta_theta_vec);
135
137 const std::vector<double> & joint_pos_vec, const std::vector<double> & delta_theta_vec,
138 const std::string & link_name, std::vector<double> & delta_x_vec);
139
141 const std::vector<double> & joint_pos_vec, const std::string & link_name,
142 Eigen::Isometry3d & transform);
143
145 const std::vector<double> & joint_pos_vec, const std::string & link_name,
146 Eigen::Matrix<double, 6, Eigen::Dynamic> & jacobian);
147
149 const std::vector<double> & joint_pos_vec, const std::string & link_name,
150 Eigen::Matrix<double, Eigen::Dynamic, 6> & jacobian_inverse);
151
153 std::vector<double> & x_a_vec, std::vector<double> & x_b_vec, double dt,
154 std::vector<double> & delta_x_vec);
155};
156
157} // namespace kinematics_interface
158
159#endif // KINEMATICS_INTERFACE__KINEMATICS_INTERFACE_HPP_
Definition kinematics_interface.hpp:45
virtual bool calculate_jacobian_inverse(const Eigen::VectorXd &joint_pos, const std::string &link_name, Eigen::Matrix< double, Eigen::Dynamic, 6 > &jacobian_inverse)=0
Calculates the jacobian inverse for a specified link using provided joint positions.
virtual bool calculate_frame_difference(Eigen::Matrix< double, 7, 1 > &x_a, Eigen::Matrix< double, 7, 1 > &x_b, double dt, Eigen::Matrix< double, 6, 1 > &delta_x)=0
Calculates the difference between two Cartesian frames.
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.
virtual bool initialize(const std::string &robot_description, std::shared_ptr< rclcpp::node_interfaces::NodeParametersInterface > parameters_interface, const std::string &param_namespace)=0
Initialize plugin. This method must be called before any other.
Definition kinematics_interface.hpp:40