@@ -45,7 +45,7 @@ def subscribe_to_robot_description(node, key="robot_description"):
45
45
node .create_subscription (String , key , callback , qos_profile )
46
46
47
47
48
- def get_joint_limits (node , use_smallest_joint_limits = True ):
48
+ def get_joint_limits (node , joints_names , use_smallest_joint_limits = True ):
49
49
global description
50
50
use_small = use_smallest_joint_limits
51
51
use_mimic = True
@@ -71,54 +71,56 @@ def get_joint_limits(node, use_smallest_joint_limits=True):
71
71
if jtype == "fixed" :
72
72
continue
73
73
name = child .getAttribute ("name" )
74
- try :
75
- limit = child . getElementsByTagName ( "limit" )[ 0 ]
74
+
75
+ if name in joints_names :
76
76
try :
77
- minval = float (limit .getAttribute ("lower" ))
78
- maxval = float (limit .getAttribute ("upper" ))
79
- except ValueError :
80
- if jtype == "continuous" :
81
- minval = - pi
82
- maxval = pi
83
- else :
77
+ limit = child .getElementsByTagName ("limit" )[0 ]
78
+ try :
79
+ minval = float (limit .getAttribute ("lower" ))
80
+ maxval = float (limit .getAttribute ("upper" ))
81
+ except ValueError :
82
+ if jtype == "continuous" :
83
+ minval = - pi
84
+ maxval = pi
85
+ else :
86
+ raise Exception (
87
+ f"Missing lower/upper position limits for the joint : { name } of type : { jtype } in the robot_description!"
88
+ )
89
+ try :
90
+ maxvel = float (limit .getAttribute ("velocity" ))
91
+ except ValueError :
84
92
raise Exception (
85
- f"Missing lower/upper position limits for the joint : { name } of type : { jtype } in the robot_description!"
93
+ f"Missing velocity limits for the joint : { name } of type : { jtype } in the robot_description!"
86
94
)
87
- try :
88
- maxvel = float (limit .getAttribute ("velocity" ))
89
- except ValueError :
95
+ except IndexError :
90
96
raise Exception (
91
- f"Missing velocity limits for the joint : { name } of type : { jtype } in the robot_description!"
97
+ f"Missing limits tag for the joint : { name } in the robot_description!"
92
98
)
93
- except IndexError :
94
- raise Exception (
95
- f"Missing limits tag for the joint : { name } in the robot_description!"
96
- )
97
- safety_tags = child .getElementsByTagName ("safety_controller" )
98
- if use_small and len (safety_tags ) == 1 :
99
- tag = safety_tags [0 ]
100
- if tag .hasAttribute ("soft_lower_limit" ):
101
- minval = max (minval , float (tag .getAttribute ("soft_lower_limit" )))
102
- if tag .hasAttribute ("soft_upper_limit" ):
103
- maxval = min (maxval , float (tag .getAttribute ("soft_upper_limit" )))
104
-
105
- mimic_tags = child .getElementsByTagName ("mimic" )
106
- if use_mimic and len (mimic_tags ) == 1 :
107
- tag = mimic_tags [0 ]
108
- entry = {"parent" : tag .getAttribute ("joint" )}
109
- if tag .hasAttribute ("multiplier" ):
110
- entry ["factor" ] = float (tag .getAttribute ("multiplier" ))
111
- if tag .hasAttribute ("offset" ):
112
- entry ["offset" ] = float (tag .getAttribute ("offset" ))
113
-
114
- dependent_joints [name ] = entry
115
- continue
116
-
117
- if name in dependent_joints :
118
- continue
119
-
120
- joint = {"min_position" : minval , "max_position" : maxval }
121
- joint ["has_position_limits" ] = jtype != "continuous"
122
- joint ["max_velocity" ] = maxvel
123
- free_joints [name ] = joint
99
+ safety_tags = child .getElementsByTagName ("safety_controller" )
100
+ if use_small and len (safety_tags ) == 1 :
101
+ tag = safety_tags [0 ]
102
+ if tag .hasAttribute ("soft_lower_limit" ):
103
+ minval = max (minval , float (tag .getAttribute ("soft_lower_limit" )))
104
+ if tag .hasAttribute ("soft_upper_limit" ):
105
+ maxval = min (maxval , float (tag .getAttribute ("soft_upper_limit" )))
106
+
107
+ mimic_tags = child .getElementsByTagName ("mimic" )
108
+ if use_mimic and len (mimic_tags ) == 1 :
109
+ tag = mimic_tags [0 ]
110
+ entry = {"parent" : tag .getAttribute ("joint" )}
111
+ if tag .hasAttribute ("multiplier" ):
112
+ entry ["factor" ] = float (tag .getAttribute ("multiplier" ))
113
+ if tag .hasAttribute ("offset" ):
114
+ entry ["offset" ] = float (tag .getAttribute ("offset" ))
115
+
116
+ dependent_joints [name ] = entry
117
+ continue
118
+
119
+ if name in dependent_joints :
120
+ continue
121
+
122
+ joint = {"min_position" : minval , "max_position" : maxval }
123
+ joint ["has_position_limits" ] = jtype != "continuous"
124
+ joint ["max_velocity" ] = maxvel
125
+ free_joints [name ] = joint
124
126
return free_joints
0 commit comments