-
Notifications
You must be signed in to change notification settings - Fork 0
/
openni_tracker.cpp
211 lines (162 loc) · 7.54 KB
/
openni_tracker.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
// openni_tracker.cpp
#include <ros/ros.h>
#include <ros/package.h>
#include <tf/transform_broadcaster.h>
#include <kdl/frames.hpp>
#include <XnOpenNI.h>
#include <XnCodecIDs.h>
#include <XnCppWrapper.h>
#include <std_msgs/String.h>
using std::string;
xn::Context g_Context;
xn::DepthGenerator g_DepthGenerator;
xn::UserGenerator g_UserGenerator;
XnBool g_bNeedPose = FALSE;
XnChar g_strPose[20] = "";
void XN_CALLBACK_TYPE User_NewUser(xn::UserGenerator& generator, XnUserID nId, void* pCookie) {
ROS_WARN("New User %d", nId);
if (g_bNeedPose)
g_UserGenerator.GetPoseDetectionCap().StartPoseDetection(g_strPose, nId);
else
g_UserGenerator.GetSkeletonCap().RequestCalibration(nId, TRUE);
}
void XN_CALLBACK_TYPE User_LostUser(xn::UserGenerator& generator, XnUserID nId, void* pCookie) {
ROS_WARN("Lost user %d", nId);
}
void XN_CALLBACK_TYPE UserCalibration_CalibrationStart(xn::SkeletonCapability& capability, XnUserID nId, void* pCookie) {
ROS_WARN("Calibration started for user %d", nId);
}
void XN_CALLBACK_TYPE UserCalibration_CalibrationEnd(xn::SkeletonCapability& capability, XnUserID nId, XnBool bSuccess, void* pCookie) {
if (bSuccess) {
ROS_WARN("Calibration complete, start tracking user %d", nId);
ros::Publisher confirmation_pub = n.advertise<std_msgs::String>("/tracker/confirmation", 1000);
std_msgs::String msg;
confirmation.publish('confirmation')
g_UserGenerator.GetSkeletonCap().StartTracking(nId);
}
else {
ROS_WARN("Calibration failed for user %d", nId);
if (g_bNeedPose)
g_UserGenerator.GetPoseDetectionCap().StartPoseDetection(g_strPose, nId);
else
g_UserGenerator.GetSkeletonCap().RequestCalibration(nId, TRUE);
}
}
void XN_CALLBACK_TYPE UserPose_PoseDetected(xn::PoseDetectionCapability& capability, XnChar const* strPose, XnUserID nId, void* pCookie) {
ROS_WARN("Pose %s detected for user %d", strPose, nId);
g_UserGenerator.GetPoseDetectionCap().StopPoseDetection(nId);
g_UserGenerator.GetSkeletonCap().RequestCalibration(nId, TRUE);
}
void publishTransform(XnUserID const& user, XnSkeletonJoint const& joint, string const& frame_id, string const& child_frame_id) {
static tf::TransformBroadcaster br;
ros::Publisher walk_pub = n.advertise<std_msgs::String>("/tracker/walk", 1000);
std_msgs::String msg;
walk.publish('walk')
g_UserGenerator.GetSkeletonCap().StartTracking(nId);
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);
char child_frame_no[128];
snprintf(child_frame_no, sizeof(child_frame_no), "%s_%d", child_frame_id.c_str(), user);
tf::Transform transform;
transform.setOrigin(tf::Vector3(x, y, z));
transform.setRotation(tf::Quaternion(qx, -qy, -qz, qw));
// #4994
tf::Transform change_frame;
change_frame.setOrigin(tf::Vector3(0, 0, 0));
tf::Quaternion frame_rotation;
frame_rotation.setEulerZYX(1.5708, 0, 1.5708);
change_frame.setRotation(frame_rotation);
transform = change_frame * transform;
br.sendTransform(tf::StampedTransform(transform, ros::Time::now(), frame_id, child_frame_no));
}
void publishTransforms(const std::string& frame_id) {
XnUserID users[15];
XnUInt16 users_count = 15;
g_UserGenerator.GetUsers(users, users_count);
for (int i = 0; i < users_count; ++i) {
XnUserID user = users[i];
if (!g_UserGenerator.GetSkeletonCap().IsTracking(user))
continue;
publishTransform(user, XN_SKEL_HEAD, frame_id, "head");
publishTransform(user, XN_SKEL_NECK, frame_id, "neck");
publishTransform(user, XN_SKEL_TORSO, frame_id, "torso");
publishTransform(user, XN_SKEL_LEFT_SHOULDER, frame_id, "left_shoulder");
publishTransform(user, XN_SKEL_LEFT_ELBOW, frame_id, "left_elbow");
publishTransform(user, XN_SKEL_LEFT_HAND, frame_id, "left_hand");
publishTransform(user, XN_SKEL_RIGHT_SHOULDER, frame_id, "right_shoulder");
publishTransform(user, XN_SKEL_RIGHT_ELBOW, frame_id, "right_elbow");
publishTransform(user, XN_SKEL_RIGHT_HAND, frame_id, "right_hand");
publishTransform(user, XN_SKEL_LEFT_HIP, frame_id, "left_hip");
publishTransform(user, XN_SKEL_LEFT_KNEE, frame_id, "left_knee");
publishTransform(user, XN_SKEL_LEFT_FOOT, frame_id, "left_foot");
publishTransform(user, XN_SKEL_RIGHT_HIP, frame_id, "right_hip");
publishTransform(user, XN_SKEL_RIGHT_KNEE, frame_id, "right_knee");
publishTransform(user, XN_SKEL_RIGHT_FOOT, frame_id, "right_foot");
}
}
#define CHECK_RC(nRetVal, what) \
if (nRetVal != XN_STATUS_OK) \
{ \
ROS_ERROR("%s failed: %s", what, xnGetStatusString(nRetVal));\
return nRetVal; \
}
int main(int argc, char **argv) {
ros::init(argc, argv, "openni_tracker");
ros::NodeHandle nh;
string configFilename = ros::package::getPath("openni_tracker") + "/openni_tracker.xml";
XnStatus nRetVal = g_Context.InitFromXmlFile(configFilename.c_str());
CHECK_RC(nRetVal, "InitFromXml");
nRetVal = g_Context.FindExistingNode(XN_NODE_TYPE_DEPTH, g_DepthGenerator);
CHECK_RC(nRetVal, "Find depth generator");
nRetVal = g_Context.FindExistingNode(XN_NODE_TYPE_USER, g_UserGenerator);
if (nRetVal != XN_STATUS_OK) {
nRetVal = g_UserGenerator.Create(g_Context);
if (nRetVal != XN_STATUS_OK) {
ROS_ERROR("NITE is likely missing: Please install NITE >= 1.5.2.21. Check the readme for download information. Error Info: User generator failed: %s", xnGetStatusString(nRetVal));
return nRetVal;
}
}
if (!g_UserGenerator.IsCapabilitySupported(XN_CAPABILITY_SKELETON)) {
ROS_INFO("Supplied user generator doesn't support skeleton");
return 1;
}
XnCallbackHandle hUserCallbacks;
g_UserGenerator.RegisterUserCallbacks(User_NewUser, User_LostUser, NULL, hUserCallbacks);
XnCallbackHandle hCalibrationCallbacks;
g_UserGenerator.GetSkeletonCap().RegisterCalibrationCallbacks(UserCalibration_CalibrationStart, UserCalibration_CalibrationEnd, NULL, hCalibrationCallbacks);
if (g_UserGenerator.GetSkeletonCap().NeedPoseForCalibration()) {
g_bNeedPose = TRUE;
if (!g_UserGenerator.IsCapabilitySupported(XN_CAPABILITY_POSE_DETECTION)) {
ROS_INFO("Pose required, but not supported");
return 1;
}
XnCallbackHandle hPoseCallbacks;
g_UserGenerator.GetPoseDetectionCap().RegisterToPoseCallbacks(UserPose_PoseDetected, NULL, NULL, hPoseCallbacks);
g_UserGenerator.GetSkeletonCap().GetCalibrationPose(g_strPose);
}
g_UserGenerator.GetSkeletonCap().SetSkeletonProfile(XN_SKEL_PROFILE_ALL);
nRetVal = g_Context.StartGeneratingAll();
CHECK_RC(nRetVal, "StartGenerating");
ros::Rate r(30);
ros::NodeHandle pnh("~");
string frame_id("openni_depth_frame");
pnh.getParam("camera_frame_id", frame_id);
while (ros::ok()) {
g_Context.WaitAndUpdateAll();
publishTransforms(frame_id);
r.sleep();
}
g_Context.Shutdown();
return 0;
}