26#ifndef TESSERACT_KINEMATICS_KDL_UTILS_H 
   27#define TESSERACT_KINEMATICS_KDL_UTILS_H 
   31#include <kdl/frames.hpp> 
   32#include <kdl/jntarray.hpp> 
   72void KDLToEigen(
const KDL::Jacobian& 
jacobian, 
const std::vector<int>& q_nrs, Eigen::Ref<Eigen::MatrixXd> matrix);
 
   79void EigenToKDL(
const Eigen::Ref<const Eigen::VectorXd>& vec, KDL::JntArray& 
joints);
 
   86void KDLToEigen(
const KDL::JntArray& 
joints, Eigen::Ref<Eigen::VectorXd> vec);
 
  102  std::vector<std::pair<std::string, std::string>> 
chains; 
 
  115                     const std::vector<std::pair<std::string, std::string>>& chains);
 
  127                     const std::string& base_name,
 
  128                     const std::string& tip_name);
 
results transform[0]
Definition: collision_core_unit.cpp:144
 
A basic scene graph using boost.
 
auto scene_graph
Definition: ikfast_kinematics_7dof_unit.cpp:51
 
Eigen::MatrixXd jacobian
Definition: kinematics_core_unit.cpp:153
 
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
Definition: macros.h:71
 
Definition: create_convex_hull.cpp:36
 
Definition: forward_kinematics.h:44
 
bool parseSceneGraph(KDLChainData &results, const tesseract_scene_graph::SceneGraph &scene_graph, const std::vector< std::pair< std::string, std::string > > &chains)
Parse KDL chain data from the scene graph.
Definition: kdl_utils.cpp:79
 
void KDLToEigen(const KDL::Frame &frame, Eigen::Isometry3d &transform)
Convert KDL::Frame to Eigen::Isometry3d.
Definition: kdl_utils.cpp:31
 
void EigenToKDL(const Eigen::Isometry3d &transform, KDL::Frame &frame)
Convert Eigen::Isometry3d to KDL::Frame.
Definition: kdl_utils.cpp:44
 
The KDLChainData struct.
Definition: kdl_utils.h:95
 
std::vector< std::string > joint_names
List of joint names.
Definition: kdl_utils.h:98
 
KDL::Tree kdl_tree
KDL tree object.
Definition: kdl_utils.h:97
 
KDL::Chain robot_chain
KDL Chain object.
Definition: kdl_utils.h:96
 
std::string tip_link_name
Link name of last kink in the kinematic object.
Definition: kdl_utils.h:100
 
std::vector< std::pair< std::string, std::string > > chains
Definition: kdl_utils.h:102
 
std::string base_link_name
Link name of first link in the kinematic object.
Definition: kdl_utils.h:99
 
std::map< std::string, int > segment_index
A map from chain link name to kdl chain segment number.
Definition: kdl_utils.h:101
 
Common Tesseract Utility Functions.
 
Kinematics utility functions.
 
object joints["j_1"]
Definition: tesseract_scene_graph_serialization_unit.cpp:224