kdl_parser.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Wim Meeussen & Levi Armstrong */
36 
37 #ifndef TESSERACT_SCENE_GRAPH_KDL_PARSER_H
38 #define TESSERACT_SCENE_GRAPH_KDL_PARSER_H
39 
42 #include <string>
43 #include <vector>
44 #include <memory>
45 #include <unordered_map>
46 #include <Eigen/Geometry>
47 
48 #include <kdl/tree.hpp>
49 #include <kdl/jacobian.hpp>
51 
53 
54 namespace tesseract_scene_graph
55 {
56 class SceneGraph;
57 class Joint;
58 class Inertial;
59 
65 KDL::Frame convert(const Eigen::Isometry3d& transform);
66 
72 Eigen::Isometry3d convert(const KDL::Frame& frame);
73 
79 KDL::Vector convert(const Eigen::Vector3d& vector);
80 
86 Eigen::Vector3d convert(const KDL::Vector& vector);
87 
93 Eigen::MatrixXd convert(const KDL::Jacobian& jacobian);
94 
100 KDL::Jacobian convert(const Eigen::MatrixXd& jacobian);
101 
108 Eigen::MatrixXd convert(const KDL::Jacobian& jacobian, const std::vector<int>& q_nrs);
109 
115 KDL::Joint convert(const std::shared_ptr<const Joint>& joint);
116 
122 KDL::RigidBodyInertia convert(const std::shared_ptr<const Inertial>& inertial);
123 
125 struct KDLTreeData
126 {
127  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
128 
129  KDL::Tree tree;
130  std::string base_link_name;
131  std::vector<std::string> joint_names;
132  std::vector<std::string> active_joint_names;
133  std::vector<std::string> floating_joint_names;
134  std::vector<std::string> link_names;
135  std::vector<std::string> active_link_names;
136  std::vector<std::string> static_link_names;
138 
139  bool operator==(const KDLTreeData& rhs) const;
140  bool operator!=(const KDLTreeData& rhs) const;
141 };
142 
149 KDLTreeData parseSceneGraph(const SceneGraph& scene_graph);
150 
165  const std::vector<std::string>& joint_names,
166  const std::unordered_map<std::string, double>& joint_values,
167  const tesseract_common::TransformMap& floating_joint_values = {});
168 
169 } // namespace tesseract_scene_graph
170 
171 #endif // TESSERACT_SCENE_GRAPH_KDL_PARSER_H
tesseract_scene_graph::KDLTreeData::active_joint_names
std::vector< std::string > active_joint_names
Definition: kdl_parser.h:164
tesseract_scene_graph::KDLTreeData::static_link_names
std::vector< std::string > static_link_names
Definition: kdl_parser.h:168
tesseract_common::TransformMap
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
tesseract_scene_graph::convert
KDL::Frame convert(const Eigen::Isometry3d &transform)
Convert Eigen::Isometry3d to KDL::Frame.
Definition: kdl_parser.cpp:83
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
tesseract_scene_graph::SceneGraph
Definition: graph.h:125
tesseract_scene_graph::KDLTreeData::link_names
std::vector< std::string > link_names
Definition: kdl_parser.h:166
tesseract_scene_graph::parseSceneGraph
KDLTreeData parseSceneGraph(const SceneGraph &scene_graph)
Convert a Tesseract SceneGraph into a KDL Tree.
Definition: kdl_parser.cpp:491
tesseract_scene_graph::KDLTreeData::base_link_name
std::string base_link_name
Definition: kdl_parser.h:162
tesseract_scene_graph::KDLTreeData::active_link_names
std::vector< std::string > active_link_names
Definition: kdl_parser.h:167
tesseract_scene_graph::KDLTreeData::floating_joint_names
std::vector< std::string > floating_joint_names
Definition: kdl_parser.h:165
tesseract_scene_graph::KDLTreeData
The KDLTreeData populated when parsing scene graph.
Definition: kdl_parser.h:157
tesseract_scene_graph::KDLTreeData::operator!=
bool operator!=(const KDLTreeData &rhs) const
Definition: kdl_parser.cpp:248
tesseract_scene_graph::KDLTreeData::joint_names
std::vector< std::string > joint_names
Definition: kdl_parser.h:163
eigen_types.h
TESSERACT_COMMON_IGNORE_WARNINGS_POP
#define TESSERACT_COMMON_IGNORE_WARNINGS_POP
tesseract_scene_graph::KDLTreeData::floating_joint_values
tesseract_common::TransformMap floating_joint_values
Definition: kdl_parser.h:169
tesseract_scene_graph::KDLTreeData::operator==
bool operator==(const KDLTreeData &rhs) const
Definition: kdl_parser.cpp:228
macros.h
tesseract_scene_graph
Definition: fwd.h:32
tesseract_scene_graph::KDLTreeData::tree
EIGEN_MAKE_ALIGNED_OPERATOR_NEW KDL::Tree tree
Definition: kdl_parser.h:161


tesseract_scene_graph
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:01:49