49 const std::string & robot_description,
50 std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface> parameters_interface,
51 const std::string & param_namespace) = 0;
62 const Eigen::VectorXd & joint_pos,
const Eigen::Matrix<double, 6, 1> & delta_x,
63 const std::string & link_name, Eigen::VectorXd & delta_theta) = 0;
74 const Eigen::VectorXd & joint_pos,
const Eigen::VectorXd & delta_theta,
75 const std::string & link_name, Eigen::Matrix<double, 6, 1> & delta_x) = 0;
85 const Eigen::VectorXd & joint_pos,
const std::string & link_name,
86 Eigen::Isometry3d & transform) = 0;
96 const Eigen::VectorXd & joint_pos,
const std::string & link_name,
97 Eigen::Matrix<double, 6, Eigen::Dynamic> & jacobian) = 0;
107 const Eigen::VectorXd & joint_pos,
const std::string & link_name,
108 Eigen::Matrix<double, Eigen::Dynamic, 6> & jacobian_inverse) = 0;
119 Eigen::Matrix<double, 7, 1> & x_a, Eigen::Matrix<double, 7, 1> & x_b,
double dt,
120 Eigen::Matrix<double, 6, 1> & delta_x) = 0;
123 std::vector<double> & joint_pos_vec,
const std::vector<double> & delta_x_vec,
124 const std::string & link_name, std::vector<double> & delta_theta_vec);
127 const std::vector<double> & joint_pos_vec,
const std::vector<double> & delta_theta_vec,
128 const std::string & link_name, std::vector<double> & delta_x_vec);
131 const std::vector<double> & joint_pos_vec,
const std::string & link_name,
132 Eigen::Isometry3d & transform);
135 const std::vector<double> & joint_pos_vec,
const std::string & link_name,
136 Eigen::Matrix<double, 6, Eigen::Dynamic> & jacobian);
139 const std::vector<double> & joint_pos_vec,
const std::string & link_name,
140 Eigen::Matrix<double, Eigen::Dynamic, 6> & jacobian_inverse);
143 std::vector<double> & x_a_vec, std::vector<double> & x_b_vec,
double dt,
144 std::vector<double> & delta_x_vec);