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