37 #ifndef TESSERACT_SCENE_GRAPH_KDL_PARSER_H
38 #define TESSERACT_SCENE_GRAPH_KDL_PARSER_H
45 #include <unordered_map>
46 #include <Eigen/Geometry>
48 #include <kdl/tree.hpp>
49 #include <kdl/jacobian.hpp>
65 KDL::Frame
convert(
const Eigen::Isometry3d& transform);
72 Eigen::Isometry3d
convert(
const KDL::Frame& frame);
79 KDL::Vector
convert(
const Eigen::Vector3d& vector);
86 Eigen::Vector3d
convert(
const KDL::Vector& vector);
93 Eigen::MatrixXd
convert(
const KDL::Jacobian& jacobian);
100 KDL::Jacobian
convert(
const Eigen::MatrixXd& jacobian);
108 Eigen::MatrixXd
convert(
const KDL::Jacobian& jacobian,
const std::vector<int>& q_nrs);
115 KDL::Joint
convert(
const std::shared_ptr<const Joint>& joint);
122 KDL::RigidBodyInertia
convert(
const std::shared_ptr<const Inertial>& inertial);
127 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
139 bool operator==(
const KDLTreeData& rhs)
const;
140 bool operator!=(
const KDLTreeData& rhs)
const;
165 const std::vector<std::string>& joint_names,
166 const std::unordered_map<std::string, double>& joint_values,
171 #endif // TESSERACT_SCENE_GRAPH_KDL_PARSER_H