18 #ifndef KINEMATICS_INTERFACE__KINEMATICS_INTERFACE_HPP_
19 #define KINEMATICS_INTERFACE__KINEMATICS_INTERFACE_HPP_
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"
48 const std::string & robot_description,
49 std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface> parameters_interface,
50 const std::string & param_namespace) = 0;
61 const Eigen::VectorXd & joint_pos,
const Eigen::Matrix<double, 6, 1> & delta_x,
62 const std::string & link_name, Eigen::VectorXd & delta_theta) = 0;
73 const Eigen::VectorXd & joint_pos,
const Eigen::VectorXd & delta_theta,
74 const std::string & link_name, Eigen::Matrix<double, 6, 1> & delta_x) = 0;
84 const Eigen::VectorXd & joint_pos,
const std::string & link_name,
85 Eigen::Isometry3d & transform) = 0;
95 const Eigen::VectorXd & joint_pos,
const std::string & link_name,
96 Eigen::Matrix<double, 6, Eigen::Dynamic> & jacobian) = 0;
106 const Eigen::VectorXd & joint_pos,
const std::string & link_name,
107 Eigen::Matrix<double, Eigen::Dynamic, 6> & jacobian_inverse) = 0;
110 std::vector<double> & joint_pos_vec,
const std::vector<double> & delta_x_vec,
111 const std::string & link_name, std::vector<double> & delta_theta_vec);
114 const std::vector<double> & joint_pos_vec,
const std::vector<double> & delta_theta_vec,
115 const std::string & link_name, std::vector<double> & delta_x_vec);
118 const std::vector<double> & joint_pos_vec,
const std::string & link_name,
119 Eigen::Isometry3d & transform);
122 const std::vector<double> & joint_pos_vec,
const std::string & link_name,
123 Eigen::Matrix<double, 6, Eigen::Dynamic> & jacobian);
126 const std::vector<double> & joint_pos_vec,
const std::string & link_name,
127 Eigen::Matrix<double, Eigen::Dynamic, 6> & jacobian_inverse);
Definition: kinematics_interface.hpp:34
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 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 ¶m_namespace)=0
Initialize plugin. This method must be called before any other.
Definition: kinematics_interface.hpp:32