ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

Running openni_tracker with multiple kinects

asked 2012-11-12 00:25:25 -0500

Hi everyone,

I am using two kinects on the same computer, and I would like to run some skeleton tracking for each of the kinects.

In order to do that, multiple solutions occured to my mind :

1) run openni_tracker for each kinect : this does not work, as openni_tracker runs on the first device it finds, without letting me selecting the device I want to use (if anyone knows how to modify it, I would be glad)

2) save the data with rosbag, then replay only one kinect, while puting an invalid device id (as said here : Tutorial Bag Recording). However, this solution does not work, and some other people had the same problem as shown in ros answers here.

I tried to go into openni code, but without success, I don't have any idea how to modify it.

My config : ROS Eletric, under Ubuntu 10.04

Any help or idea would be appreciated,

Thank you in advance,

edit retag flag offensive close merge delete

4 Answers

Sort by ยป oldest newest most voted
7

answered 2012-11-25 20:12:55 -0500

updated 2014-08-07 11:11:12 -0500

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)
edit flag offensive delete link more

Comments

This answer works also on ROS Groovy and Ubuntu 12.10 :-)

Stephane.M gravatar image Stephane.M  ( 2013-02-07 00:36:54 -0500 )edit

Hi there!

I'm using your code Stephane.M, but unfortunately, when I try it out, it doesn't work in 100%, namely: at the begining I had problem with core dump (now it doesn't happen), but now I noticed, that it doesn't matter if I chose device 1 or 2, it always connects to the same Kinect.

da-na gravatar image da-na  ( 2013-04-22 05:15:45 -0500 )edit

Hi, sorry for late response. If you want to connect to kinect 1, put both variables to 1. If you want to connect to kinect 2, put first 2 then 1. It should work then. (Personnally, I put it in my launch file). See my edit in my answer.

Stephane.M gravatar image Stephane.M  ( 2013-04-22 20:43:32 -0500 )edit

Thank you Stephane!! :)

da-na gravatar image da-na  ( 2013-04-23 02:13:02 -0500 )edit

Hi there! where can i find the multiple_kinect/tracker.xml file ? pls tell so i would be able to use your code... Thanks :-)

CryptoKnight gravatar image CryptoKnight  ( 2014-08-07 07:39:21 -0500 )edit

This is an openni File... I edit my answer to show you the content, but you should have found it by yourself :-S Good luck anyway ^^

Stephane.M gravatar image Stephane.M  ( 2014-08-07 11:10:01 -0500 )edit

Stephane, thanks for all your work! I'm having trouble duplicating all you changes. Do you have the working code available in a repository that I could clone?

dinosaur gravatar image dinosaur  ( 2015-08-18 12:47:13 -0500 )edit
0

answered 2015-08-18 21:31:44 -0500

dinosaur gravatar image

updated 2015-08-18 21:34:59 -0500

Building on Stephane's work, I made some changes so that you can select the device automatically based on a serial number input as a ros parameter.

Usage looks like this:

rosrun openni_tracker openni_tracker _desired_serial:=B00312327745048B

Notable additions to the code include:

  1. Getting the USB port number by calling deviceNodeInfo.GetCreationInfo() and parsing out the value after the last /.

  2. Calling lsusb via popen (fp = popen("lsusb -v -d 045e:02ae", "r");) and parsing the output to match usb port to serial number. This depends on the system's implementation and formatting of lsusb so it's probably the most fragile part.

  3. Calling ros::param::get("~desired_serial", desiredSerial) to get the user's desired serial number from the ros parameter server.

Code is online here: https://github.com/lrperlmu/openni_tr... . More details can be found in the readme.

edit flag offensive delete link more
0

answered 2014-02-19 02:32:40 -0500

Latif Anjum gravatar image

I am getting error: [ERROR] [1392819332.186358415]: Find user generator failed: Can't create any node of the requested type!. I have searched a lot but no success. I have ros fuerte on ubuntu 12.04. openni.launch is working fine and i can see images on rviz. rosrun openni_tracker openni_tracker is generating above error.

edit flag offensive delete link more

Comments

1

You should try switching NITE versions. That has usually fixed your error for me. See answer from @isura here: http://answers.ros.org/question/42654/openninite-incompatible-in-fuertegroovy-on-precise/?answer=52137

jarvisschultz gravatar image jarvisschultz  ( 2014-02-19 02:48:02 -0500 )edit
0

answered 2013-04-03 16:14:23 -0500

Tariq gravatar image

updated 2013-04-03 16:16:04 -0500

Hey Stephane,

Me again :) I am now stuck with tracking multiple person with single kinect, somewhat similar to this one. I've already posted a question (http://answers.ros.org/question/59917/multiple-user-tracking-using-pi_tracker/). Your help will be highly appreciated.

Thanks.

edit flag offensive delete link more

Question Tools

2 followers

Stats

Asked: 2012-11-12 00:25:25 -0500

Seen: 1,810 times

Last updated: Aug 18 '15