44 std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface> parameters_interface,
45 const std::string & end_effector_name) = 0;
56 const Eigen::VectorXd & joint_pos,
const Eigen::Matrix<double, 6, 1> & delta_x,
57 const std::string & link_name, Eigen::VectorXd & delta_theta) = 0;
68 const Eigen::VectorXd & joint_pos,
const Eigen::VectorXd & delta_theta,
69 const std::string & link_name, Eigen::Matrix<double, 6, 1> & delta_x) = 0;
79 const Eigen::VectorXd & joint_pos,
const std::string & link_name,
80 Eigen::Isometry3d & transform) = 0;
90 const Eigen::VectorXd & joint_pos,
const std::string & link_name,
91 Eigen::Matrix<double, 6, Eigen::Dynamic> & jacobian) = 0;
94 std::vector<double> & joint_pos_vec,
const std::vector<double> & delta_x_vec,
95 const std::string & link_name, std::vector<double> & delta_theta_vec);
98 const std::vector<double> & joint_pos_vec,
const std::vector<double> & delta_theta_vec,
99 const std::string & link_name, std::vector<double> & delta_x_vec);
102 const std::vector<double> & joint_pos_vec,
const std::string & link_name,
103 Eigen::Isometry3d & transform);
106 const std::vector<double> & joint_pos_vec,
const std::string & link_name,
107 Eigen::Matrix<double, 6, Eigen::Dynamic> & jacobian);