59 const std::string & robot_description,
60 std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface> parameters_interface,
61 const std::string & param_namespace) = 0;
72 const Eigen::VectorXd & joint_pos,
const Eigen::Matrix<double, 6, 1> & delta_x,
73 const std::string & link_name, Eigen::VectorXd & delta_theta) = 0;
84 const Eigen::VectorXd & joint_pos,
const Eigen::VectorXd & delta_theta,
85 const std::string & link_name, Eigen::Matrix<double, 6, 1> & delta_x) = 0;
95 const Eigen::VectorXd & joint_pos,
const std::string & link_name,
96 Eigen::Isometry3d & transform) = 0;
106 const Eigen::VectorXd & joint_pos,
const std::string & link_name,
107 Eigen::Matrix<double, 6, Eigen::Dynamic> & jacobian) = 0;
117 const Eigen::VectorXd & joint_pos,
const std::string & link_name,
118 Eigen::Matrix<double, Eigen::Dynamic, 6> & jacobian_inverse) = 0;
121 std::vector<double> & joint_pos_vec,
const std::vector<double> & delta_x_vec,
122 const std::string & link_name, std::vector<double> & delta_theta_vec);
125 const std::vector<double> & joint_pos_vec,
const std::vector<double> & delta_theta_vec,
126 const std::string & link_name, std::vector<double> & delta_x_vec);
129 const std::vector<double> & joint_pos_vec,
const std::string & link_name,
130 Eigen::Isometry3d & transform);
133 const std::vector<double> & joint_pos_vec,
const std::string & link_name,
134 Eigen::Matrix<double, 6, Eigen::Dynamic> & jacobian);
137 const std::vector<double> & joint_pos_vec,
const std::string & link_name,
138 Eigen::Matrix<double, Eigen::Dynamic, 6> & jacobian_inverse);