Update
This commit is contained in:
parent
5df779725a
commit
a32f63559b
@ -9,7 +9,11 @@ if __name__ == '__main__':
|
|||||||
|
|
||||||
rate = rospy.Rate(10.0)
|
rate = rospy.Rate(10.0)
|
||||||
while not rospy.is_shutdown():
|
while not rospy.is_shutdown():
|
||||||
(trans,rot) = listener.lookupTransform('/left_gripper', '/base', rospy.Time(0))
|
try:
|
||||||
|
(trans,rot) = listener.lookupTransform('/left_gripper', '/base', rospy.Time(0))
|
||||||
|
except(tf.LookupException, tf.ConnectivityException, tf.ExtrapolationException):
|
||||||
|
continue
|
||||||
|
|
||||||
Translation = [trans.x , trans.y , trans.z]
|
Translation = [trans.x , trans.y , trans.z]
|
||||||
Quaternion = [rot.x , rot.y , rot.z, rot.w]
|
Quaternion = [rot.x , rot.y , rot.z, rot.w]
|
||||||
Angles = tf.transformations.euler_from_quaternion([rot.x , rot.y ,
|
Angles = tf.transformations.euler_from_quaternion([rot.x , rot.y ,
|
||||||
|
|||||||
@ -52,7 +52,6 @@ class tf_service():
|
|||||||
# rospy.init_node('gazebo_link_subscriber')
|
# rospy.init_node('gazebo_link_subscriber')
|
||||||
rospy.Subscriber("/gazebo/link_states", LinkStates, self._callback)
|
rospy.Subscriber("/gazebo/link_states", LinkStates, self._callback)
|
||||||
a+=1
|
a+=1
|
||||||
print('this shit on? ', str(a))
|
|
||||||
# spin() simply keeps python from exiting until this node is stopped
|
# spin() simply keeps python from exiting until this node is stopped
|
||||||
rospy.spin()
|
rospy.spin()
|
||||||
|
|
||||||
|
|||||||
Loading…
Reference in New Issue
Block a user