Skip to content

Instantly share code, notes, and snippets.

@omangin
Created April 18, 2012 15:03
Show Gist options
  • Save omangin/2414166 to your computer and use it in GitHub Desktop.
Save omangin/2414166 to your computer and use it in GitHub Desktop.
Module to connect to a kinect through ROS + OpenNI and access the skeleton postures.
# encoding: utf-8
"""Module to connect to a kinect through ROS + OpenNI and access
the skeleton postures.
"""
import roslib
roslib.load_manifest('ros_skeleton_recorder')
import rospy
import tf
BASE_FRAME = '/openni_depth_frame'
FRAMES = [
'head',
'neck',
'torso',
'left_shoulder',
'left_elbow',
'left_hand',
'left_hip',
'left_knee',
'left_foot',
'right_shoulder',
'right_elbow',
'right_hand',
'right_hip',
'right_knee',
'right_foot',
]
LAST = rospy.Duration()
class Kinect:
def __init__(self, name='kinect_listener', user=1):
rospy.init_node(name, anonymous=True)
self.listener = tf.TransformListener()
self.user = user
def get_posture(self):
"""Returns a list of frames constituted by a translation matrix
and a rotation matrix.
Raises IndexError when a frame can't be found (which happens if
the requested user is not calibrated).
"""
try:
frames = []
for frame in FRAMES:
trans, rot = self.listener.lookupTransform(BASE_FRAME,
"/%s_%d" % (frame, self.user), LAST)
frames.append((trans, rot))
return frames
except (tf.LookupException,
tf.ConnectivityException,
tf.ExtrapolationException):
raise IndexError
@joaosalvadoo
Copy link

when i try to run the following code

"

Import the kinect class from your file

from yourfile import Kinect

Init the Kinect object

kin = Kinect()

Get values

for i in xrange(10):
print i, kin.posicao_corpo()
"
i got this error:
"
Traceback (most recent call last):
File "/home/joao/ros_ws/tracking_py/src/tracking.py", line 64, in
print i, kin.posicao_corpo()
File "/home/joao/ros_ws/tracking_py/src/tracking.py", line 57, in posicao_corpo
raise IndexError
IndexError
"
do you know why?
if i run" rosrun tf tf_echo /openni_depth_frame /head_1" i can see the quartenation and rotation clearly so, i dont know why i have this error.
thanks

@AankitaDebroy
Copy link

It happens because the TF frame may not be available all the time. So its better to wait until the next TF frame is available.
Add the following line :

self.listener.waitForTransform(BASE_FRAME, "/%s_%d" % (frame, self.user), rospy.Time(), rospy.Duration(4.0)

before:
(trans, rot) = self.listener.lookupTransform(BASE_FRAME,"/%s_%d" % (frame, self.user), LAST)

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment