45 std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface> parameters_interface,
46 const std::string & end_effector_name) = 0;
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;
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;
80 const Eigen::VectorXd & joint_pos,
const std::string & link_name,
81 Eigen::Isometry3d & transform) = 0;
91 const Eigen::VectorXd & joint_pos,
const std::string & link_name,
92 Eigen::Matrix<double, 6, Eigen::Dynamic> & jacobian) = 0;
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);
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);
103 const std::vector<double> & joint_pos_vec,
const std::string & link_name,
104 Eigen::Isometry3d & transform);
107 const std::vector<double> & joint_pos_vec,
const std::string & link_name,
108 Eigen::Matrix<double, 6, Eigen::Dynamic> & jacobian);