37 from geometry_msgs.msg
import Vector3
39 roslib.load_manifest(
'hand_kinematics')
41 if __name__ ==
'__main__':
42 rospy.init_node(
'tf_tippos_publisher')
45 tip_pos_pub.append(rospy.Publisher(
'fftip/position/', Vector3, queue_size=10))
46 tip_pos_pub.append(rospy.Publisher(
'mftip/position/', Vector3, queue_size=10))
47 tip_pos_pub.append(rospy.Publisher(
'rftip/position/', Vector3, queue_size=10))
48 tip_pos_pub.append(rospy.Publisher(
'lftip/position/', Vector3, queue_size=10))
49 tip_pos_pub.append(rospy.Publisher(
'thtip/position/', Vector3, queue_size=10))
50 rate = rospy.Rate(10.0)
51 while not rospy.is_shutdown():
53 listener.waitForTransform(
54 '/rh_palm',
'/rh_fftip', rospy.Time.now(), rospy.Duration(1.0))
56 (trans, rot) = listener.lookupTransform(
57 '/rh_palm',
'/rh_fftip', rospy.Time(0))
60 tip_pos_pub[0].publish(Vector3(trans[0], trans[1], trans[2]))
62 (trans, rot) = listener.lookupTransform(
63 '/rh_palm',
'/rh_mftip', rospy.Time(0))
66 tip_pos_pub[1].publish(Vector3(trans[0], trans[1], trans[2]))
68 (trans, rot) = listener.lookupTransform(
69 '/rh_palm',
'/rh_rftip', rospy.Time(0))
72 tip_pos_pub[2].publish(Vector3(trans[0], trans[1], trans[2]))
74 (trans, rot) = listener.lookupTransform(
75 '/rh_palm',
'/rh_lftip', rospy.Time(0))
78 tip_pos_pub[3].publish(Vector3(trans[0], trans[1], trans[2]))
80 (trans, rot) = listener.lookupTransform(
81 '/rh_palm',
'/rh_thtip', rospy.Time(0))
84 tip_pos_pub[4].publish(Vector3(trans[0], trans[1], trans[2]))