1414# See the License for the specific language governing permissions and
1515# limitations under the License.
1616
17+ # Code inspired on the joint_state_publisher package by David Lu!!!
18+ # https://github.com/ros/robot_model/blob/indigo-devel/
19+ # joint_state_publisher/joint_state_publisher/joint_state_publisher
20+
1721# TODO: Use urdf_parser_py.urdf instead. I gave it a try, but got
1822# Exception: Required attribute not set in XML: upper
1923# upper is an optional attribute, so I don't understand what's going on
@@ -33,21 +37,24 @@ def callback(msg):
3337 description = msg .data
3438
3539
36- def get_joint_limits (node , key = "robot_description" , use_smallest_joint_limits = True ):
37- global description
38- use_small = use_smallest_joint_limits
39- use_mimic = True
40-
41- # Code inspired on the joint_state_publisher package by David Lu!!!
42- # https://github.com/ros/robot_model/blob/indigo-devel/
43- # joint_state_publisher/joint_state_publisher/joint_state_publisher
44-
40+ def subscribe_to_robot_description (node , key = "robot_description" ):
4541 qos_profile = rclpy .qos .QoSProfile (depth = 1 )
4642 qos_profile .durability = rclpy .qos .DurabilityPolicy .TRANSIENT_LOCAL
4743 qos_profile .reliability = rclpy .qos .ReliabilityPolicy .RELIABLE
4844
49- node .create_subscription (String , "/robot_description" , callback , qos_profile )
50- rclpy .spin_once (node )
45+ node .create_subscription (String , key , callback , qos_profile )
46+
47+
48+ def get_joint_limits (node , use_smallest_joint_limits = True ):
49+ global description
50+ use_small = use_smallest_joint_limits
51+ use_mimic = True
52+
53+ count = 0
54+ while description == "" and count < 10 :
55+ print ("Waiting for the robot_description!" )
56+ count += 1
57+ rclpy .spin_once (node , timeout_sec = 1.0 )
5158
5259 free_joints = {}
5360 dependent_joints = {}
@@ -66,21 +73,27 @@ def get_joint_limits(node, key="robot_description", use_smallest_joint_limits=Tr
6673 name = child .getAttribute ("name" )
6774 try :
6875 limit = child .getElementsByTagName ("limit" )[0 ]
69- except IndexError :
70- continue
71- if jtype == "continuous" :
72- minval = - pi
73- maxval = pi
74- else :
7576 try :
7677 minval = float (limit .getAttribute ("lower" ))
7778 maxval = float (limit .getAttribute ("upper" ))
7879 except ValueError :
79- continue
80- try :
81- maxvel = float (limit .getAttribute ("velocity" ))
82- except ValueError :
83- continue
80+ if jtype == "continuous" :
81+ minval = - pi
82+ maxval = pi
83+ else :
84+ raise Exception (
85+ f"Missing lower/upper position limits for the joint : { name } of type : { jtype } in the robot_description!"
86+ )
87+ try :
88+ maxvel = float (limit .getAttribute ("velocity" ))
89+ except ValueError :
90+ raise Exception (
91+ f"Missing velocity limits for the joint : { name } of type : { jtype } in the robot_description!"
92+ )
93+ except IndexError :
94+ raise Exception (
95+ f"Missing limits tag for the joint : { name } in the robot_description!"
96+ )
8497 safety_tags = child .getElementsByTagName ("safety_controller" )
8598 if use_small and len (safety_tags ) == 1 :
8699 tag = safety_tags [0 ]
0 commit comments