00001
00002
00003 #include <ros/ros.h>
00004 #include <ros/package.h>
00005 #include <tf/transform_broadcaster.h>
00006 #include <kdl/frames.hpp>
00007
00008 #include <XnOpenNI.h>
00009 #include <XnCodecIDs.h>
00010 #include <XnCppWrapper.h>
00011
00012 using std::string;
00013
00014 xn::Context g_Context;
00015 xn::DepthGenerator g_DepthGenerator;
00016 xn::UserGenerator g_UserGenerator;
00017
00018 XnBool g_bNeedPose = FALSE;
00019 XnChar g_strPose[20] = "";
00020
00021 void XN_CALLBACK_TYPE User_NewUser(xn::UserGenerator& generator, XnUserID nId, void* pCookie) {
00022 printf("New User %d\n", nId);
00023
00024 if (g_bNeedPose)
00025 g_UserGenerator.GetPoseDetectionCap().StartPoseDetection(g_strPose, nId);
00026 else
00027 g_UserGenerator.GetSkeletonCap().RequestCalibration(nId, TRUE);
00028 }
00029
00030 void XN_CALLBACK_TYPE User_LostUser(xn::UserGenerator& generator, XnUserID nId, void* pCookie) {
00031 printf("Lost user %d\n", nId);
00032 }
00033
00034 void XN_CALLBACK_TYPE UserCalibration_CalibrationStart(xn::SkeletonCapability& capability, XnUserID nId, void* pCookie) {
00035 printf("Calibration started for user %d\n", nId);
00036 }
00037
00038 void XN_CALLBACK_TYPE UserCalibration_CalibrationEnd(xn::SkeletonCapability& capability, XnUserID nId, XnBool bSuccess, void* pCookie) {
00039 if (bSuccess) {
00040 printf("Calibration complete, start tracking user %d\n", nId);
00041 g_UserGenerator.GetSkeletonCap().StartTracking(nId);
00042 }
00043 else {
00044 printf("Calibration failed for user %d\n", nId);
00045 if (g_bNeedPose)
00046 g_UserGenerator.GetPoseDetectionCap().StartPoseDetection(g_strPose, nId);
00047 else
00048 g_UserGenerator.GetSkeletonCap().RequestCalibration(nId, TRUE);
00049 }
00050 }
00051
00052 void XN_CALLBACK_TYPE UserPose_PoseDetected(xn::PoseDetectionCapability& capability, XnChar const* strPose, XnUserID nId, void* pCookie) {
00053 printf("Pose %s detected for user %d\n", strPose, nId);
00054 g_UserGenerator.GetPoseDetectionCap().StopPoseDetection(nId);
00055 g_UserGenerator.GetSkeletonCap().RequestCalibration(nId, TRUE);
00056 }
00057
00058 void publishTransform(XnUserID const& user, XnSkeletonJoint const& joint, string const& frame_id, string const& child_frame_id) {
00059 static tf::TransformBroadcaster br;
00060
00061 XnSkeletonJointPosition joint_position;
00062 g_UserGenerator.GetSkeletonCap().GetSkeletonJointPosition(user, joint, joint_position);
00063 double x = joint_position.position.X / 1000.0;
00064 double y = joint_position.position.Y / 1000.0;
00065 double z = joint_position.position.Z / 1000.0;
00066
00067 XnSkeletonJointOrientation joint_orientation;
00068 g_UserGenerator.GetSkeletonCap().GetSkeletonJointOrientation(user, joint, joint_orientation);
00069
00070 XnFloat* m = joint_orientation.orientation.elements;
00071 KDL::Rotation rotation(m[0], m[1], m[2],
00072 m[3], m[4], m[5],
00073 m[6], m[7], m[8]);
00074 double qx, qy, qz, qw;
00075 rotation.GetQuaternion(qx, qy, qz, qw);
00076
00077 tf::Transform transform;
00078 transform.setOrigin(tf::Vector3(x, y, z));
00079 transform.setRotation(tf::Quaternion(qx, qy, qz, qw));
00080 br.sendTransform(tf::StampedTransform(transform, ros::Time::now(), frame_id, child_frame_id));
00081 }
00082
00083 void publishTransforms(const std::string& frame_id) {
00084 XnUserID users[15];
00085 XnUInt16 users_count = 15;
00086 g_UserGenerator.GetUsers(users, users_count);
00087
00088 for (int i = 0; i < users_count; ++i) {
00089 XnUserID user = users[i];
00090 if (!g_UserGenerator.GetSkeletonCap().IsTracking(user))
00091 continue;
00092
00093
00094 publishTransform(user, XN_SKEL_HEAD, frame_id, "head");
00095 publishTransform(user, XN_SKEL_NECK, frame_id, "neck");
00096 publishTransform(user, XN_SKEL_TORSO, frame_id, "torso");
00097
00098 publishTransform(user, XN_SKEL_LEFT_SHOULDER, frame_id, "left_shoulder");
00099 publishTransform(user, XN_SKEL_LEFT_ELBOW, frame_id, "left_elbow");
00100 publishTransform(user, XN_SKEL_LEFT_HAND, frame_id, "left_hand");
00101
00102 publishTransform(user, XN_SKEL_RIGHT_SHOULDER, frame_id, "right_shoulder");
00103 publishTransform(user, XN_SKEL_RIGHT_ELBOW, frame_id, "right_elbow");
00104 publishTransform(user, XN_SKEL_RIGHT_HAND, frame_id, "right_hand");
00105
00106 publishTransform(user, XN_SKEL_LEFT_HIP, frame_id, "left_hip");
00107 publishTransform(user, XN_SKEL_LEFT_KNEE, frame_id, "left_knee");
00108 publishTransform(user, XN_SKEL_LEFT_FOOT, frame_id, "left_foot");
00109
00110 publishTransform(user, XN_SKEL_RIGHT_HIP, frame_id, "right_hip");
00111 publishTransform(user, XN_SKEL_RIGHT_KNEE, frame_id, "right_knee");
00112 publishTransform(user, XN_SKEL_RIGHT_FOOT, frame_id, "right_foot");
00113 }
00114 }
00115
00116 #define CHECK_RC(nRetVal, what) \
00117 if (nRetVal != XN_STATUS_OK) \
00118 { \
00119 printf("%s failed: %s\n", what, xnGetStatusString(nRetVal));\
00120 return nRetVal; \
00121 }
00122
00123 int main(int argc, char **argv) {
00124 ros::init(argc, argv, "openni_tracker");
00125 ros::NodeHandle nh;
00126
00127 string configFilename = ros::package::getPath("openni_tracker") + "/openni_tracker.xml";
00128 XnStatus nRetVal = g_Context.InitFromXmlFile(configFilename.c_str());
00129 CHECK_RC(nRetVal, "InitFromXml");
00130
00131 nRetVal = g_Context.FindExistingNode(XN_NODE_TYPE_DEPTH, g_DepthGenerator);
00132 CHECK_RC(nRetVal, "Find depth generator");
00133
00134 nRetVal = g_Context.FindExistingNode(XN_NODE_TYPE_USER, g_UserGenerator);
00135 if (nRetVal != XN_STATUS_OK) {
00136 nRetVal = g_UserGenerator.Create(g_Context);
00137 CHECK_RC(nRetVal, "Find user generator");
00138 }
00139
00140 if (!g_UserGenerator.IsCapabilitySupported(XN_CAPABILITY_SKELETON)) {
00141 printf("Supplied user generator doesn't support skeleton\n");
00142 return 1;
00143 }
00144
00145 XnCallbackHandle hUserCallbacks;
00146 g_UserGenerator.RegisterUserCallbacks(User_NewUser, User_LostUser, NULL, hUserCallbacks);
00147
00148 XnCallbackHandle hCalibrationCallbacks;
00149 g_UserGenerator.GetSkeletonCap().RegisterCalibrationCallbacks(UserCalibration_CalibrationStart, UserCalibration_CalibrationEnd, NULL, hCalibrationCallbacks);
00150
00151 if (g_UserGenerator.GetSkeletonCap().NeedPoseForCalibration()) {
00152 g_bNeedPose = TRUE;
00153 if (!g_UserGenerator.IsCapabilitySupported(XN_CAPABILITY_POSE_DETECTION)) {
00154 printf("Pose required, but not supported\n");
00155 return 1;
00156 }
00157
00158 XnCallbackHandle hPoseCallbacks;
00159 g_UserGenerator.GetPoseDetectionCap().RegisterToPoseCallbacks(UserPose_PoseDetected, NULL, NULL, hPoseCallbacks);
00160
00161 g_UserGenerator.GetSkeletonCap().GetCalibrationPose(g_strPose);
00162 }
00163
00164 g_UserGenerator.GetSkeletonCap().SetSkeletonProfile(XN_SKEL_PROFILE_ALL);
00165
00166 nRetVal = g_Context.StartGeneratingAll();
00167 CHECK_RC(nRetVal, "StartGenerating");
00168
00169 ros::Rate r(30);
00170
00171
00172 ros::NodeHandle pnh("~");
00173 string frame_id("openni_depth_frame");
00174 pnh.getParam("camera_frame_id", frame_id);
00175
00176 while (ros::ok()) {
00177 g_Context.WaitAndUpdateAll();
00178 publishTransforms(frame_id);
00179 r.sleep();
00180 }
00181
00182 g_Context.Shutdown();
00183 return 0;
00184 }