Hey everybody !
I finally managed to do it :-)
In order to have two different trackers you can create two files (named tracker_1 and tracker_2 for example), with a modified version of the openni_tracker given below. I hope it will help many people ;-)
Some lines in my code may not be usefull, and are the result of my many tests...
In the second tracker, Don't forget to change lines :
108 to 126 : in the second file, change all the names (head become head2, etc), otherwise if 1 personn is detected in each kinect, the frames will be jumping from one to the other
line 138 . ros::init(argc, argv, "tracker_1");
line 141. string configFilename = ros::package::getPath("multiple_kinect") + "/tracker.xml";
line 328. string frame_id("/kinect1_depth_frame");
Here is the code :
// openni_tracker_modified.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>
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_INFO("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_INFO("Lost user %d", nId);
}
void XN_CALLBACK_TYPE UserCalibration_CalibrationStart(xn::SkeletonCapability& capability, XnUserID nId, void* pCookie) {
ROS_INFO("Calibration started for user %d", nId);
}
void XN_CALLBACK_TYPE UserCalibration_CalibrationEnd(xn::SkeletonCapability& capability, XnUserID nId, XnBool bSuccess, void* pCookie) {
if (bSuccess) {
ROS_INFO("Calibration complete, start tracking user %d", nId);
g_UserGenerator.GetSkeletonCap().StartTracking(nId);
}
else {
ROS_INFO("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_INFO("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;
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));//g_Device
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 ...
(more)