openni_tracker/Transform depth
I am using the openni_tracker with a Kinect, and I have written a node to receive the transforms from it. Is there a variable that will tell me the distance between the sensor and a joint of a person being tracked?
Update: In openni_tracker.cpp, this code is found:
void publishTransform(XnUserID const& user, XnSkeletonJoint const& joint, string const& frame_id, string const& child_frame_id) {
static tf::TransformBroadcaster br;
XnSkeletonJointPosition joint_position;
g_UserGenerator.GetSkeletonCap().GetSkeletonJointPosition(user, joint, joint_position);
double x = joint_position.position.X / 1000.0;
double y = joint_position.position.Y / 1000.0;
double z = joint_position.position.Z / 1000.0;
XnSkeletonJointOrientation joint_orientation;
g_UserGenerator.GetSkeletonCap().GetSkeletonJointOrientation(user, joint, joint_orientation);
XnFloat* m = joint_orientation.orientation.elements;
KDL::Rotation rotation(m[0], m[1], m[2],
m[3], m[4], m[5],
m[6], m[7], m[8]);
double qx, qy, qz, qw;
rotation.GetQuaternion(qx, qy, qz, qw);
tf::Transform transform;
transform.setOrigin(tf::Vector3(x, y, z));
transform.setRotation(tf::Quaternion(qx, qy, qz, qw));
br.sendTransform(tf::StampedTransform(transform, ros::Time::now(), frame_id, child_frame_id));
}
It appears that the Vector3 in transform is equal to joint_position.position which is supposed to be the exact position(not how much the joint has moved). Also, the output data seems to show that this is true. Therefore, I believe the problem has been solved.