34 match_link =
"(.*)<link[^>]*name\s*=\s*\"pedestal\"[^>]*>.*?[^<]<\/link>(.*)" 35 match_joint =
"(.*)<joint[^>]*name\s*=\s*\"pedestal_fixed\"[^>]*>.*?[^<]<\/joint>(.*)" 37 if __name__ ==
'__main__':
39 rospy.init_node(
'urdf_remove_pedestal', anonymous=
True)
40 param_src = rospy.get_param(
'~param_src',
"/robot_description")
41 param_dest = rospy.get_param(
'~param_dest',
"/robot_description_mod")
42 urdf = rospy.get_param(param_src,
"")
45 obj = re.match(match_link, urdf, re.S)
47 urdf = obj.group(1) + obj.group(2)
49 rospy.loginfo(
"Removed link 'pedestal'")
51 rospy.logwarn(
"Failed to find link 'pedestal'")
53 obj = re.match(match_joint, urdf, re.S)
55 urdf = obj.group(1) + obj.group(2)
57 rospy.loginfo(
"Removed joint 'pedestal_fixed'")
59 rospy.logwarn(
"Failed to find joint 'pedestal_fixed'")
61 rospy.set_param(param_dest, urdf)
63 rospy.loginfo(
"Updated parameter '%s'", param_dest)
65 rospy.loginfo(
"Copied parameter '%s' to '%s'", param_src, param_dest)
67 rospy.logwarn(
"Parameter '%s' not found", param_src)
68 except rospy.ROSInterruptException:
pass