ros2_control - rolling
Loading...
Searching...
No Matches
kinematics_interface_pinocchio.hpp
1// Copyright (c) 2024, Saif Sidhik.
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_PINOCCHIO__KINEMATICS_INTERFACE_PINOCCHIO_HPP_
19#define KINEMATICS_INTERFACE_PINOCCHIO__KINEMATICS_INTERFACE_PINOCCHIO_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 "kinematics_interface/kinematics_interface.hpp"
29#include "rclcpp/node_interfaces/node_parameters_interface.hpp"
30
31#include "pinocchio/algorithm/frames.hpp"
32#include "pinocchio/algorithm/geometry.hpp"
33#include "pinocchio/algorithm/jacobian.hpp"
34#include "pinocchio/algorithm/joint-configuration.hpp"
35#include "pinocchio/parsers/urdf.hpp"
36
38{
40{
41public:
42 bool initialize(
43 const std::string & robot_description,
44 std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface> parameters_interface,
45 const std::string & param_namespace) override;
46
48 const Eigen::VectorXd & joint_pos, const Eigen::Matrix<double, 6, 1> & delta_x,
49 const std::string & link_name, Eigen::VectorXd & delta_theta) override;
50
52 const Eigen::VectorXd & joint_pos, const Eigen::VectorXd & delta_theta,
53 const std::string & link_name, Eigen::Matrix<double, 6, 1> & delta_x) override;
54
56 const Eigen::VectorXd & joint_pos, const std::string & link_name,
57 Eigen::Isometry3d & transform) override;
58
60 const Eigen::VectorXd & joint_pos, const std::string & link_name,
61 Eigen::Matrix<double, 6, Eigen::Dynamic> & jacobian) override;
62
64 const Eigen::VectorXd & joint_pos, const std::string & link_name,
65 Eigen::Matrix<double, Eigen::Dynamic, 6> & jacobian_inverse) override;
66
68 Eigen::Matrix<double, 7, 1> & x_a, Eigen::Matrix<double, 7, 1> & x_b, double dt,
69 Eigen::Matrix<double, 6, 1> & delta_x) override;
70
71private:
72 // verification methods
73 bool verify_initialized();
74 bool verify_link_name(const std::string & link_name);
75 bool verify_joint_vector(const Eigen::VectorXd & joint_vector);
76 bool verify_jacobian(const Eigen::Matrix<double, 6, Eigen::Dynamic> & jacobian);
77 bool verify_jacobian_inverse(const Eigen::Matrix<double, Eigen::Dynamic, 6> & jacobian_inverse);
78 bool verify_period(const double dt);
79
80 bool initialized = false;
81 std::string root_name_;
82 Eigen::Index num_joints_;
83
84 pinocchio::Model model_;
85 std::shared_ptr<pinocchio::Data> data_;
86 Eigen::VectorXd q_;
87 Eigen::MatrixXd jacobian_;
88 Eigen::Matrix<double, Eigen::Dynamic, 6> jacobian_inverse_;
89 Eigen::MatrixXd frame_tf_;
90
91 std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface> parameters_interface_;
92 std::unordered_map<std::string, int> link_name_map_;
93 double alpha; // damping term for Jacobian inverse
94 Eigen::MatrixXd I;
95};
96
97} // namespace kinematics_interface_pinocchio
98
99#endif // KINEMATICS_INTERFACE_PINOCCHIO__KINEMATICS_INTERFACE_PINOCCHIO_HPP_
Definition kinematics_interface.hpp:45
Definition kinematics_interface_pinocchio.hpp:40
bool initialize(const std::string &robot_description, std::shared_ptr< rclcpp::node_interfaces::NodeParametersInterface > parameters_interface, const std::string &param_namespace) override
Initialize plugin. This method must be called before any other.
Definition kinematics_interface_pinocchio.cpp:26
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_pinocchio.cpp:264
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_pinocchio.cpp:239
bool calculate_jacobian_inverse(const Eigen::VectorXd &joint_pos, const std::string &link_name, Eigen::Matrix< double, Eigen::Dynamic, 6 > &jacobian_inverse) override
Calculates the jacobian inverse for a specified link using provided joint positions.
Definition kinematics_interface_pinocchio.cpp:313
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_pinocchio.cpp:289
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_pinocchio.cpp:342
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) override
Calculates the difference between two Cartesian frames.
Definition kinematics_interface_pinocchio.cpp:382
Definition kinematics_interface_pinocchio.hpp:38