Tesseract 0.28.4
Loading...
Searching...
No Matches
kdl_utils.h File Reference

Tesseract KDL utility functions. More...

#include <tesseract/common/macros.h>
#include <kdl/frames.hpp>
#include <kdl/jntarray.hpp>
#include <kdl/tree.hpp>
#include <kdl/chain.hpp>
#include <Eigen/Geometry>
#include <tesseract/scene_graph/fwd.h>

Classes

struct  tesseract::kinematics::KDLChainData
 The KDLChainData struct. More...
 

Functions

void tesseract::kinematics::KDLToEigen (const KDL::Frame &frame, Eigen::Isometry3d &transform)
 Convert KDL::Frame to Eigen::Isometry3d.
 
void tesseract::kinematics::EigenToKDL (const Eigen::Isometry3d &transform, KDL::Frame &frame)
 Convert Eigen::Isometry3d to KDL::Frame.
 
void tesseract::kinematics::KDLToEigen (const KDL::Jacobian &jacobian, Eigen::Ref< Eigen::MatrixXd > matrix)
 Convert KDL::Jacobian to Eigen::Matrix.
 
void tesseract::kinematics::KDLToEigen (const KDL::Jacobian &jacobian, const std::vector< int > &q_nrs, Eigen::Ref< Eigen::MatrixXd > matrix)
 Convert a subset of KDL::Jacobian to Eigen::Matrix.
 
void tesseract::kinematics::EigenToKDL (const Eigen::Ref< const Eigen::VectorXd > &vec, KDL::JntArray &joints)
 Convert Eigen::Vector to KDL::JntArray.
 
void tesseract::kinematics::KDLToEigen (const KDL::JntArray &joints, Eigen::Ref< Eigen::VectorXd > vec)
 Convert KDL::JntArray to Eigen::Vector.
 
bool tesseract::kinematics::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.
 
bool tesseract::kinematics::parseSceneGraph (KDLChainData &results, const tesseract::scene_graph::SceneGraph &scene_graph, const std::string &base_name, const std::string &tip_name)
 Parse KDL chain data from the scene graph.
 

Detailed Description

Tesseract KDL utility functions.

Author
Levi Armstrong
Date
May 27, 2018
License
Software License Agreement (Apache License)
Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License.

Function Documentation

◆ KDLToEigen() [1/4]

void tesseract::kinematics::KDLToEigen ( const KDL::Frame &  frame,
Eigen::Isometry3d &  transform 
)

Convert KDL::Frame to Eigen::Isometry3d.

Parameters
frameInput KDL Frame
transformOutput Eigen transform (Isometry3d)

◆ EigenToKDL() [1/2]

void tesseract::kinematics::EigenToKDL ( const Eigen::Isometry3d &  transform,
KDL::Frame &  frame 
)

Convert Eigen::Isometry3d to KDL::Frame.

Parameters
transformInput Eigen transform (Isometry3d)
frameOutput KDL Frame

◆ KDLToEigen() [2/4]

void tesseract::kinematics::KDLToEigen ( const KDL::Jacobian &  jacobian,
Eigen::Ref< Eigen::MatrixXd >  matrix 
)

Convert KDL::Jacobian to Eigen::Matrix.

Parameters
jacobianInput KDL Jacobian
matrixOutput Eigen MatrixXd

◆ KDLToEigen() [3/4]

void tesseract::kinematics::KDLToEigen ( const KDL::Jacobian &  jacobian,
const std::vector< int > &  q_nrs,
Eigen::Ref< Eigen::MatrixXd >  matrix 
)

Convert a subset of KDL::Jacobian to Eigen::Matrix.

Parameters
jacobianInput KDL Jacobian
q_nrsInput the columns to use
matrixOutput Eigen MatrixXd

◆ EigenToKDL() [2/2]

void tesseract::kinematics::EigenToKDL ( const Eigen::Ref< const Eigen::VectorXd > &  vec,
KDL::JntArray &  joints 
)

Convert Eigen::Vector to KDL::JntArray.

Parameters
vecInput Eigen vector
jointsOutput KDL joint array

◆ KDLToEigen() [4/4]

void tesseract::kinematics::KDLToEigen ( const KDL::JntArray &  joints,
Eigen::Ref< Eigen::VectorXd >  vec 
)

Convert KDL::JntArray to Eigen::Vector.

Parameters
jointsInput KDL joint array
vecOutput Eigen vector

◆ parseSceneGraph() [1/2]

bool tesseract::kinematics::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.

Parameters
resultsKDL Chain data
scene_graphThe Scene Graph
chainsA vector of link pairs that represent a chain which all get concatenated together. The firts link should be the base link and the second link should the tip link of the chain.
Returns
True if successful otherwise false

◆ parseSceneGraph() [2/2]

bool tesseract::kinematics::parseSceneGraph ( KDLChainData results,
const tesseract::scene_graph::SceneGraph scene_graph,
const std::string &  base_name,
const std::string &  tip_name 
)

Parse KDL chain data from the scene graph.

Parameters
resultsKDL Chain data
scene_graphThe Scene Graph
base_nameThe base link name of chain
tip_nameThe tip link name of chain
Returns
True if successful otherwise false