ros2_control - humble
Loading...
Searching...
No Matches
kinematics_interface_kdl.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_KDL__KINEMATICS_INTERFACE_KDL_HPP_
19#define KINEMATICS_INTERFACE_KDL__KINEMATICS_INTERFACE_KDL_HPP_
20
21#include <memory>
22#include <string>
23#include <unordered_map>
24#include <vector>
25
26#include "eigen3/Eigen/Core"
27#include "eigen3/Eigen/LU"
28#include "kdl/chainfksolverpos_recursive.hpp"
29#include "kdl/chainfksolvervel_recursive.hpp"
30#include "kdl/chainjnttojacsolver.hpp"
31#include "kdl/treejnttojacsolver.hpp"
32#include "kdl_parser/kdl_parser.hpp"
33#include "kinematics_interface/kinematics_interface.hpp"
34#include "rclcpp/node_interfaces/node_parameters_interface.hpp"
35#include "tf2_eigen_kdl/tf2_eigen_kdl.hpp"
36
38{
40{
41public:
42 bool initialize(
43 std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface> parameters_interface,
44 const std::string & end_effector_name) override;
45
47 const Eigen::VectorXd & joint_pos, const Eigen::Matrix<double, 6, 1> & delta_x,
48 const std::string & link_name, Eigen::VectorXd & delta_theta) override;
49
51 const Eigen::VectorXd & joint_pos, const Eigen::VectorXd & delta_theta,
52 const std::string & link_name, Eigen::Matrix<double, 6, 1> & delta_x) override;
53
55 const Eigen::VectorXd & joint_pos, const std::string & link_name,
56 Eigen::Isometry3d & transform) override;
57
59 const Eigen::VectorXd & joint_pos, const std::string & link_name,
60 Eigen::Matrix<double, 6, Eigen::Dynamic> & jacobian) override;
61
62private:
63 // verification methods
64 bool verify_initialized();
65 bool verify_link_name(const std::string & link_name);
66 bool verify_joint_vector(const Eigen::VectorXd & joint_vector);
67 bool verify_jacobian(const Eigen::Matrix<double, 6, Eigen::Dynamic> & jacobian);
68
69 bool initialized = false;
70 std::string root_name_;
71 size_t num_joints_;
72 KDL::Chain chain_;
73 std::shared_ptr<KDL::ChainFkSolverPos_recursive> fk_pos_solver_;
74 KDL::JntArray q_;
75 KDL::Frame frame_;
76 std::shared_ptr<KDL::Jacobian> jacobian_;
77 std::shared_ptr<KDL::ChainJntToJacSolver> jac_solver_;
78 std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface> parameters_interface_;
79 std::unordered_map<std::string, int> link_name_map_;
80 double alpha; // damping term for Jacobian inverse
81 Eigen::MatrixXd I;
82};
83
84} // namespace kinematics_interface_kdl
85
86#endif // KINEMATICS_INTERFACE_KDL__KINEMATICS_INTERFACE_KDL_HPP_
Definition kinematics_interface.hpp:34
Definition kinematics_interface_kdl.hpp:40
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) override
Convert joint delta-theta to Cartesian delta-x.
Definition kinematics_interface_kdl.cpp:74
bool calculate_link_transform(const Eigen::VectorXd &joint_pos, const std::string &link_name, Eigen::Isometry3d &transform) override
Calculates the joint transform for a specified link using provided joint positions.
Definition kinematics_interface_kdl.cpp:147
bool initialize(std::shared_ptr< rclcpp::node_interfaces::NodeParametersInterface > parameters_interface, const std::string &end_effector_name) override
Initialize plugin. This method must be called before any other.
Definition kinematics_interface_kdl.cpp:23
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) override
Convert Cartesian delta-x to joint delta-theta, using the Jacobian.
Definition kinematics_interface_kdl.cpp:97
bool calculate_jacobian(const Eigen::VectorXd &joint_pos, const std::string &link_name, Eigen::Matrix< double, 6, Eigen::Dynamic > &jacobian) override
Calculates the jacobian for a specified link using provided joint positions.
Definition kinematics_interface_kdl.cpp:125
Definition kinematics_interface_kdl.hpp:38