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

Revision history [back]

Hi there!

It has been almost 4 months since this question was posted. Recently I had the same problem as the one that Joe reports in his question. I don't own a PR2 (yet! ;P) but I was having trouble executing MIT Kinect Demo's hand_detector in a no-monitor environment. So, I would like to share the solution just in case anybody else has the same problem.

As Joe said, the file main.cpp inside skeletal_tracker has a bunch of calls to OpenGL/GLUT code. The problem is that if you do this:

//glInit(&argc, argv);
//glutMainLoop();
ros::spin();

Then the function glutDisplay will never be called. And inside that function is where they get all the data from kinect, process it and publish the skeleton topics.

So the solution could be: create a new function to do the same as glutDisplay but without all the GUI stuff. The new function would look like this:

void publishSkeletons(void)
{
  xn::SceneMetaData sceneMD;
  xn::DepthMetaData depthMD;
  g_DepthGenerator.GetMetaData(depthMD);

  //Read next available data
  g_Context.WaitAndUpdateAll();
  ros::Time tstamp = ros::Time::now();

  //Process the data
  g_DepthGenerator.GetMetaData(depthMD);
  g_UserGenerator.GetUserPixels(0, sceneMD);
  std::vector<mapping_msgs::PolygonalMap> pmaps;
  body_msgs::Skeletons skels;
  getSkels(pmaps,skels);
  ROS_DEBUG("skels size %d \n",pmaps.size());
  if(pmaps.size()){

    skels.header.stamp=tstamp;
    skels.header.seq = depthMD.FrameID();
    skels.header.frame_id="/openni_depth_optical_frame";
    skel_pub.publish(skels);
    pmaps.front().header.stamp=tstamp;
    pmaps.front().header.seq = depthMD.FrameID();
    pmaps.front().header.frame_id="/openni_depth_optical_frame";
    pmap_pub.publish(pmaps[0]);
  }
}

And then change the unwanted calls to OpenGL/GLUT stuff

glInit(&argc, argv);
glutMainLoop();

for this other calls:

ros::Rate loop_rate(30);

while (ros::ok())
{

  publishSkeletons();
  ros::spinOnce();
  loop_rate.sleep();

}

It works perfectly for me, I hope somebody else finds it useful.