43 std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface> parameters_interface,
44 const std::string & end_effector_name)
override;
47 const Eigen::VectorXd & joint_pos,
const Eigen::Matrix<double, 6, 1> & delta_x,
48 const std::string & link_name, Eigen::VectorXd & delta_theta)
override;
51 const Eigen::VectorXd & joint_pos,
const Eigen::VectorXd & delta_theta,
52 const std::string & link_name, Eigen::Matrix<double, 6, 1> & delta_x)
override;
55 const Eigen::VectorXd & joint_pos,
const std::string & link_name,
56 Eigen::Isometry3d & transform)
override;
59 const Eigen::VectorXd & joint_pos,
const std::string & link_name,
60 Eigen::Matrix<double, 6, Eigen::Dynamic> & jacobian)
override;
64 bool verify_initialized();
65 bool verify_link_name(
const std::string & link_name);
66 bool verify_joint_vector(
const Eigen::VectorXd & joint_vector);
67 bool verify_jacobian(
const Eigen::Matrix<double, 6, Eigen::Dynamic> & jacobian);
69 bool initialized =
false;
70 std::string root_name_;
73 std::shared_ptr<KDL::ChainFkSolverPos_recursive> fk_pos_solver_;
76 std::shared_ptr<KDL::Jacobian> jacobian_;
77 std::shared_ptr<KDL::ChainJntToJacSolver> jac_solver_;
78 std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface> parameters_interface_;
79 std::unordered_map<std::string, int> link_name_map_;