ros2_control - humble
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
33{
35{
36public:
37 KinematicsInterface() = default;
38
39 virtual ~KinematicsInterface() = default;
40
44 virtual bool initialize(
45 std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface> parameters_interface,
46 const std::string & end_effector_name) = 0;
47
57 const Eigen::VectorXd & joint_pos, const Eigen::Matrix<double, 6, 1> & delta_x,
58 const std::string & link_name, Eigen::VectorXd & delta_theta) = 0;
59
69 const Eigen::VectorXd & joint_pos, const Eigen::VectorXd & delta_theta,
70 const std::string & link_name, Eigen::Matrix<double, 6, 1> & delta_x) = 0;
71
80 const Eigen::VectorXd & joint_pos, const std::string & link_name,
81 Eigen::Isometry3d & transform) = 0;
82
90 virtual bool calculate_jacobian(
91 const Eigen::VectorXd & joint_pos, const std::string & link_name,
92 Eigen::Matrix<double, 6, Eigen::Dynamic> & jacobian) = 0;
93
95 std::vector<double> & joint_pos_vec, const std::vector<double> & delta_x_vec,
96 const std::string & link_name, std::vector<double> & delta_theta_vec);
97
99 const std::vector<double> & joint_pos_vec, const std::vector<double> & delta_theta_vec,
100 const std::string & link_name, std::vector<double> & delta_x_vec);
101
103 const std::vector<double> & joint_pos_vec, const std::string & link_name,
104 Eigen::Isometry3d & transform);
105
107 const std::vector<double> & joint_pos_vec, const std::string & link_name,
108 Eigen::Matrix<double, 6, Eigen::Dynamic> & jacobian);
109};
110
111} // namespace kinematics_interface
112
113#endif // KINEMATICS_INTERFACE__KINEMATICS_INTERFACE_HPP_
Definition kinematics_interface.hpp:35
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:33