1
+ # Copyright 2019 Open Source Robotics Foundation, Inc.
2
+ # All rights reserved.
3
+ #
4
+ # Software License Agreement (BSD License 2.0)
5
+ #
6
+ # Redistribution and use in source and binary forms, with or without
7
+ # modification, are permitted provided that the following conditions
8
+ # are met:
9
+ #
10
+ # * Redistributions of source code must retain the above copyright
11
+ # notice, this list of conditions and the following disclaimer.
12
+ # * Redistributions in binary form must reproduce the above
13
+ # copyright notice, this list of conditions and the following
14
+ # disclaimer in the documentation and/or other materials provided
15
+ # with the distribution.
16
+ # * Neither the name of the copyright holder nor the names of its
17
+ # contributors may be used to endorse or promote products derived
18
+ # from this software without specific prior written permission.
19
+ #
20
+ # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21
+ # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22
+ # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23
+ # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24
+ # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25
+ # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26
+ # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27
+ # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28
+ # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29
+ # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30
+ # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31
+ # POSSIBILITY OF SUCH DAMAGE.
32
+
1
33
from __future__ import print_function
2
34
3
35
import urdf_parser_py .urdf as urdf
7
39
def treeFromFile (filename ):
8
40
"""
9
41
Construct a PyKDL.Tree from an URDF file.
42
+
10
43
:param filename: URDF file path
11
44
"""
12
-
13
45
with open (filename ) as urdf_file :
14
46
return treeFromUrdfModel (urdf .URDF .from_xml_string (urdf_file .read ()))
15
47
16
- def treeFromParam (param ):
17
- """
18
- Construct a PyKDL.Tree from an URDF in a ROS parameter.
19
- :param param: Parameter name, ``str``
20
- """
21
-
22
- return treeFromUrdfModel (urdf .URDF .from_parameter_server ())
23
-
24
48
def treeFromString (xml ):
25
49
"""
26
50
Construct a PyKDL.Tree from an URDF xml string.
51
+
27
52
:param xml: URDF xml string, ``str``
28
53
"""
29
-
30
54
return treeFromUrdfModel (urdf .URDF .from_xml_string (xml ))
31
55
32
56
def _toKdlPose (pose ):
@@ -49,8 +73,7 @@ def _toKdlInertia(i):
49
73
kdl .RotationalInertia (inertia .ixx , inertia .iyy , inertia .izz , inertia .ixy , inertia .ixz , inertia .iyz ));
50
74
51
75
def _toKdlJoint (jnt ):
52
-
53
- fixed = lambda j ,F : kdl .Joint (j .name , kdl .Joint .None )
76
+ fixed = lambda j ,F : kdl .Joint (j .name , kdl .Joint .JointType (8 ))
54
77
rotational = lambda j ,F : kdl .Joint (j .name , F .p , F .M * kdl .Vector (* j .axis ), kdl .Joint .RotAxis )
55
78
translational = lambda j ,F : kdl .Joint (j .name , F .p , F .M * kdl .Vector (* j .axis ), kdl .Joint .TransAxis )
56
79
@@ -67,8 +90,6 @@ def _toKdlJoint(jnt):
67
90
return type_map [jnt .type ](jnt , _toKdlPose (jnt .origin ))
68
91
69
92
def _add_children_to_tree (robot_model , root , tree ):
70
-
71
-
72
93
# constructs the optional inertia
73
94
inert = kdl .RigidBodyInertia (0 )
74
95
if root .inertial :
@@ -108,7 +129,6 @@ def treeFromUrdfModel(robot_model, quiet=False):
108
129
:param robot_model: URDF xml string, ``str``
109
130
:param quiet: If true suppress messages to stdout, ``bool``
110
131
"""
111
-
112
132
root = robot_model .link_map [robot_model .get_root ()]
113
133
114
134
if root .inertial and not quiet :
@@ -122,5 +142,5 @@ def treeFromUrdfModel(robot_model, quiet=False):
122
142
if not _add_children_to_tree (robot_model , robot_model .link_map [child ], tree ):
123
143
ok = False
124
144
break
125
-
145
+
126
146
return (ok , tree )
0 commit comments