body_tracker.cpp
Go to the documentation of this file.
00001 /*
00002  *****************************************************************
00003  * Copyright (c) 2015 \n
00004  * Fraunhofer Institute for Manufacturing Engineering
00005  * and Automation (IPA) \n\n
00006  *
00007  *****************************************************************
00008  *
00009  * \note
00010  * Project name: Care-O-bot
00011  * \note
00012  * ROS stack name: cob_people_perception
00013  * \note
00014  * ROS package name: cob_openni2_tracker
00015  *
00016  * \author
00017  * Author: Olha Meyer
00018  * \author
00019  * Supervised by: Richard Bormann
00020  *
00021  * \date Date of creation: 01.11.2014
00022  *
00023  * \brief
00024  * functions for detecting people within a depth image
00025  * current approach: read the current video flow and detect people using OpenNI and NiTE2
00026  *
00027  *****************************************************************
00028  *
00029  * Redistribution and use in source and binary forms, with or without
00030  * modification, are permitted provided that the following conditions are met:
00031  *
00032  * - Redistributions of source code must retain the above copyright
00033  * notice, this list of conditions and the following disclaimer. \n
00034  * - Redistributions in binary form must reproduce the above copyright
00035  * notice, this list of conditions and the following disclaimer in the
00036  * documentation and/or other materials provided with the distribution. \n
00037  * - Neither the name of the Fraunhofer Institute for Manufacturing
00038  * Engineering and Automation (IPA) nor the names of its
00039  * contributors may be used to endorse or promote products derived from
00040  * this software without specific prior written permission. \n
00041  *
00042  * This program is free software: you can redistribute it and/or modify
00043  * it under the terms of the GNU Lesser General Public License LGPL as
00044  * published by the Free Software Foundation, either version 3 of the
00045  * License, or (at your option) any later version.
00046  *
00047  * This program is distributed in the hope that it will be useful,
00048  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00049  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
00050  * GNU Lesser General Public License LGPL for more details.
00051  *
00052  * You should have received a copy of the GNU Lesser General Public
00053  * License LGPL along with this program.
00054  * If not, see <http://www.gnu.org/licenses/>.
00055  *
00056  ****************************************************************/
00057 
00058 /*
00059  * Other Copyrights :
00060  *
00061  ********************************************************
00062  *                                                        *
00063  *   PrimeSense NiTE 2.0 - User Viewer Sample             *
00064  *   Copyright (C) 2012 PrimeSense Ltd.                   *
00065  *   (For a license distribution please see               *
00066  *     the package information):                          *
00067  **********************************************************/
00068 
00069 
00070 #if (defined _WIN32)
00071 #define PRIu64 "llu"
00072 #else
00073 #define __STDC_FORMAT_MACROS
00074 #include <inttypes.h>
00075 #endif
00076 
00077 #include "sensor_msgs/PointCloud2.h"
00078 #include "cob_openni2_tracker/body_tracker.h"
00079 //#include <GL/glut.h>
00080 #include <cob_openni2_tracker/NiteSampleUtilities.h>
00081 #include <math.h>
00082 #include <stdio.h>
00083 
00084 //screen and texture measures
00085 #define GL_WIN_SIZE_X   640
00086 #define GL_WIN_SIZE_Y   512
00087 #define TEXTURE_SIZE    256
00088 #define MAX_USERS 10
00089 #define MIN_NUM_CHUNKS(data_size, chunk_size)   ((((data_size)-1) / (chunk_size) + 1))
00090 #define MIN_CHUNKS_SIZE(data_size, chunk_size)  (MIN_NUM_CHUNKS(data_size, chunk_size) * (chunk_size))
00091 
00092 #define USER_MESSAGE(msg) {\
00093                 sprintf(userStatusLabels[user.getId()], "%s", msg);\
00094                 printf("[%08" PRIu64 "] User #%d:\t%s\n", ts, user.getId(), msg);}
00095 
00096 float Colors[][3] = {{1, 0, 0}, {0, 1, 0}, {0, 0, 1}, {1, 1, 1}};
00097 bool visibleUsers[MAX_USERS] = {false};
00098 int colorCount = 3;
00099 nite::SkeletonState skeletonStates[MAX_USERS] = {nite::SKELETON_NONE};
00100 char userStatusLabels[MAX_USERS][100] = {{0}};
00101 char generalMessage[100] = {0};
00102 static std::string detector_ = "camera";
00103 
00104 using namespace std;
00105 using namespace message_filters;
00106 
00107 /*
00108  * BodyTracker constructor: loads the parameter on the parameter server and
00109  * advertises subscribes and publishes.
00110  */
00111 BodyTracker::BodyTracker(ros::NodeHandle nh_priv)
00112 :pcl_cloud_(new pcl::PointCloud<pcl::PointXYZRGB>), tracked_users_(new list<nite::UserData>()), m_poseUser(0), transform_broadcaster_(), nh_(nh_priv)
00113 {
00114         marker_id_ = 0;
00115         init_counter_color_image_ = 0;
00116         init_counter_point_cloud_ = 0;
00117         shutdown_ = false;
00118 
00119         it_ = 0;
00120         m_pTexMap_ = 0;
00121         m_pUserTracker = 0;
00122 
00123         //nh_ = nh_priv;
00124         // Get Tracker Parameters
00125         if(!nh_.getParam("depth_optical_frame_id", depth_optical_frame_)){
00126                 ROS_WARN("depth_optical_frame_id was not found on Param Server! See your launch file!");
00127                 nh_.shutdown();
00128                 finalize();
00129         }
00130 
00131         if(!nh_.getParam("tf_prefix", tf_prefix_)){
00132                 ROS_WARN("tf_prefix was not found on Param Server! See your launch file!");
00133                 nh_.shutdown();
00134                 finalize();
00135         }
00136 
00137 //      if(!nh_.getParam("relative_frame", rel_frame_)){
00138 //              ROS_WARN("relative_frame was not found on Param Server! See your launch file!");
00139 //              nh_.shutdown();
00140 //              finalize();
00141 //      }
00142 
00143         std::cout << "\n---------------------------\nPeople Tracker Detection Parameters (CAMERA):\n---------------------------\n";
00144         //parameters from a YAML File
00145         nh_.param("drawSkeleton", drawSkeleton_, false);
00146         std::cout << "drawSkeleton = " << drawSkeleton_ << "\n";
00147         nh_.param("drawCenterOfMass", drawCenterOfMass_, false);
00148         std::cout << "drawCenterOfMass = " << drawCenterOfMass_ << "\n";
00149         nh_.param("drawUserName", drawUserName_, true);
00150         std::cout << "drawUserName = " << drawUserName_ << "\n";
00151         nh_.param("drawBoundingBox", drawBoundingBox_, true);
00152         std::cout << "drawBoundingBox = " << drawBoundingBox_ << "\n";
00153         nh_.param("drawBackground", drawBackground_, false);
00154         std::cout << "drawBackground = " << drawBackground_ << "\n";
00155         nh_.param("drawDepth", drawDepth_, false);
00156         std::cout << "drawDepth = " << drawDepth_ << "\n";
00157         nh_.param("drawFrames", drawFrames_, false);
00158         std::cout << "drawFrames = " << drawFrames_ << "\n";
00159         nh_.param("poseTimeoutToExit", poseTimeoutToExit_, 2000);
00160         std::cout << "poseTimeoutToExit = " << poseTimeoutToExit_ << "\n";
00161         bool standalone_without_camera_driver = false;
00162         nh_.param("standalone_without_camera_driver", standalone_without_camera_driver, false);
00163         std::cout << "standalone_without_camera_driver = " << standalone_without_camera_driver << "\n";
00164 
00165         tracked_users_ = new list<nite::UserData>();
00166 
00167         it_ = new image_transport::ImageTransport(nh_);
00168         image_sub_.registerCallback(boost::bind(&BodyTracker::imageCallback, this, _1));
00169         image_sub_.subscribe(*it_, "color_image_topic", 1);
00170         image_pub_ = it_->advertise("colorimage_out", 1);
00171 
00172         pcl_sub_ = nh_.subscribe("point_cloud_topic", 1, &BodyTracker::pointcloudCallback, this);
00173 
00174         ros::Time start_time = ros::Time::now();
00175         while(standalone_without_camera_driver==false)
00176         {
00177                 if (init_counter_color_image_>3 && init_counter_point_cloud_>3)
00178                         break;
00179                 if ((ros::Time::now()-start_time).sec > 300)
00180                 {
00181                         ROS_ERROR("The camera driver does not seem to work properly, not enough image and point cloud messages received during the last 300s.");
00182                         shutdown_ = true;
00183                         return;
00184                 }
00185         }
00186 
00187         pcl_sub_.shutdown();
00188 
00189         vis_pub_ = nh_.advertise<visualization_msgs::Marker>( "visualization_marker", 10);
00190         if (drawDepth_==true)
00191                 pcl_pub_ = nh_.advertise<pcl::PointCloud<pcl::PointXYZRGB> >("points_body_tracker", 1); // original point cloud with all points that belong to one tracked person colored in a individual color
00192         people_pub_ = nh_.advertise<cob_perception_msgs::People>("people", 1);          // detections
00193 
00194         ROS_INFO("Create BodyTracker.\n");
00195         m_pUserTracker = new nite::UserTracker;
00196         pcl_cloud_->points.clear();
00197 
00198         init();
00199 }
00200 
00201 
00202 /*
00203  * A callback function for reading and modifying a color video stream.
00204  * Uses a list of currently tracked people.
00205  *
00206  * @param color_image_msg : received sensor message
00207  */
00208 void BodyTracker::imageCallback(const sensor_msgs::ImageConstPtr& color_image_msg)
00209 {
00210         init_counter_color_image_++;
00211 
00212         cv_bridge::CvImageConstPtr cv_ptr;
00213 
00214         try
00215         {
00216                 cv_ptr = cv_bridge::toCvShare(color_image_msg, sensor_msgs::image_encodings::BGR8);
00217         }catch (cv_bridge::Exception& e)
00218         {
00219                 ROS_ERROR("PeopleDetection: cv_bridge exception: %s", e.what());
00220                 return;
00221         }
00222         cv::Mat color_image_ = cv_ptr->image;
00223         int height = color_image_msg->height;
00224         int width = color_image_msg->width;
00225 
00226         //if the list of tracked people not empty, proceed drawing
00227         if(!tracked_users_->empty())
00228         {
00229                 for(std::list<nite::UserData>::iterator iter_ = tracked_users_->begin();
00230                                 iter_ != tracked_users_->end(); ++iter_)
00231                 {
00232                         if((*iter_).getCenterOfMass().x != 0 && (*iter_).getCenterOfMass().y != 0 && (*iter_).getCenterOfMass().z != 0)
00233                         {
00234                                 int max_x = /*width - */(*iter_).getBoundingBox().max.x;
00235                                 int max_y = (*iter_).getBoundingBox().max.y;
00236                                 int min_x = /*width - */(*iter_).getBoundingBox().min.x;
00237                                 int min_y = (*iter_).getBoundingBox().min.y;
00238 
00239                                 double center_x = (*iter_).getCenterOfMass().x;
00240                                 double center_y = (*iter_).getCenterOfMass().y;
00241 
00242                                 int r = 255*Colors[(*iter_).getId() % colorCount][0];
00243                                 int g = 255*Colors[(*iter_).getId() % colorCount][1];
00244                                 int b = 255*Colors[(*iter_).getId() % colorCount][2];
00245 
00246                                 if(drawBoundingBox_)
00247                                 {
00248                                         cv::rectangle(color_image_, cv::Point(min_x, min_y), cv::Point(max_x, max_y), CV_RGB(r, g, b), 2);
00249                                 }
00250 
00251                                 if(drawCenterOfMass_)
00252                                 {
00253                                         cv::circle(color_image_, cv::Point(100, 100), 10, CV_RGB(r, g, b));
00254                                 }
00255                                 if(drawUserName_)
00256                                 {
00257                                         //drawUserName((*iter_), color_image, cv::Point(100, 100));
00258                                 }
00259                         }
00260                 }
00261         }
00262         cv::waitKey(10);
00263         // Output modified video stream
00264         image_pub_.publish(cv_ptr->toImageMsg());
00265 }
00266 
00267 void BodyTracker::pointcloudCallback(const sensor_msgs::PointCloud2::ConstPtr& pointcloud)
00268 {
00269         // dummy function
00270         init_counter_point_cloud_++;
00271 }
00272 
00273 BodyTracker::~BodyTracker()
00274 {
00275         //shutdown node
00276         finalize();
00277 }
00278 
00279 void BodyTracker::finalize()
00280 {
00281         ros::spinOnce();
00282         if (it_ != 0)
00283                 delete it_;
00284         if (m_pTexMap_ != 0)
00285                 delete[] m_pTexMap_;
00286         if (m_pUserTracker)
00287                 delete m_pUserTracker;
00288         if (device_.isValid() == true)
00289                 device_.close();
00290         nite::NiTE::shutdown();
00291         openni::OpenNI::shutdown();
00292 }
00293 
00294 /*
00295  * Initializes OpenNI and NiTE, loads a camera device and creates a video stream.
00296  */
00297 void BodyTracker::init()
00298 {
00299         m_pTexMap_ = NULL;
00300 
00301         openni::Status rc = openni::OpenNI::initialize();
00302         if (rc != openni::STATUS_OK)
00303         {
00304                 printf("Failed to initialize OpenNI\n%s\n", openni::OpenNI::getExtendedError());
00305                 nh_.shutdown();
00306                 return;
00307         }
00308         const char* device_Uri = openni::ANY_DEVICE;
00309 
00310         rc = device_.open(device_Uri);
00311         if (rc != openni::STATUS_OK)
00312         {
00313                 printf("Failed to open device_\n%s\n", openni::OpenNI::getExtendedError());
00314                 nh_.shutdown();
00315                 return;
00316         }
00317 
00318         rc = depthSensor_.create(device_, openni::SENSOR_DEPTH);
00319         if (rc != openni::STATUS_OK)
00320         {
00321                 printf("Failed to create a video stream \n%s\n", openni::OpenNI::getExtendedError());
00322                 nh_.shutdown();
00323                 return;
00324         }
00325 
00326         nite::NiTE::initialize();
00327         if (m_pUserTracker->create(&device_) != nite::STATUS_OK)
00328         {
00329                 printf(" Get data for NiTE failed\n");
00330                 nh_.shutdown();
00331                 return;
00332         }
00333 }
00334 
00335 /*
00336  * A loop function to track people.
00337  *
00338  * Firstly, it gets the first snapshot of a depth frame,
00339  * does the segmentation of the scene and starts the UserTracker algorithm
00340  * to detect possible users, which are saved in a UserMap. Each User gets specific
00341  * information(i.a. skeleton, position of joints, detected status).
00342  *
00343  * Secondly, it composes a Point Cloud according to the Usermap information
00344  * and publishes it on a given topic.
00345  *
00346  * At last, it goes through all possible users and puts the visible once
00347  * in the tracked_users_ list:
00348  * - If the user becomes visible/tracked, it is added to the list.
00349  * - If the user is lost, it is erased from the list.
00350  * - If the user is already in the list, its data is updated.
00351  *
00352  */
00353 void BodyTracker::runTracker()
00354 {
00355         while(shutdown_ ==false && nh_.ok() && ros::ok())
00356         {
00357                 nite::UserTrackerFrameRef userTrackerFrame;
00358                 openni::VideoFrameRef depthFrame;
00359 
00360                 nite::Status rc = m_pUserTracker->readFrame(&userTrackerFrame);
00361                 if (rc != nite::STATUS_OK)
00362                 {
00363                         printf("GetNextData failed\n");
00364                         return;
00365                 }
00366 
00367                 depthFrame = userTrackerFrame.getDepthFrame();
00368 
00369                 if (m_pTexMap_ == NULL)
00370                 {
00371                         // Texture map init
00372                         m_nTexMapX = MIN_CHUNKS_SIZE(depthFrame.getVideoMode().getResolutionX(), TEXTURE_SIZE);
00373                         m_nTexMapY = MIN_CHUNKS_SIZE(depthFrame.getVideoMode().getResolutionY(), TEXTURE_SIZE);
00374                         m_pTexMap_ = new openni::RGB888Pixel[m_nTexMapX * m_nTexMapY];
00375                 }
00376                 const nite::UserMap& userLabels = userTrackerFrame.getUserMap();
00377 
00378                 if (depthFrame.isValid() && drawDepth_)
00379                 {
00380                         calculateHistogram(m_pDepthHist, MAX_DEPTH, depthFrame);
00381                 }
00382                 memset(m_pTexMap_, 0, m_nTexMapX*m_nTexMapY*sizeof(openni::RGB888Pixel));
00383                 float factor[3] = {1, 1, 1};
00384 
00385                 //construct pcl
00386                 if (depthFrame.isValid() && drawDepth_)
00387                 {
00388                         const nite::UserId* pLabels = userLabels.getPixels();
00389 
00390                         const openni::DepthPixel* pDepthRow = (const openni::DepthPixel*)depthFrame.getData();
00391                         openni::RGB888Pixel* pTexRow = m_pTexMap_ + depthFrame.getCropOriginY() * m_nTexMapX;
00392                         int rowSize = depthFrame.getStrideInBytes() / sizeof(openni::DepthPixel);
00393                         float dX, dY, dZ;
00394 
00395                         pcl_cloud_->resize(depthFrame.getHeight()*depthFrame.getWidth());
00396                         pcl_cloud_->width = depthFrame.getWidth();
00397                         pcl_cloud_->height = depthFrame.getHeight();
00398 
00399                         for (int y = 0; y < depthFrame.getHeight(); ++y)
00400                         {
00401                                 const openni::DepthPixel* pDepth = pDepthRow;
00402                                 openni::RGB888Pixel* pTex = pTexRow + depthFrame.getCropOriginX();
00403 
00404                                 for (int x = 0; x < depthFrame.getWidth(); ++x, ++pDepth, ++pTex, ++pLabels)
00405                                 {
00406                                         if (*pLabels == 0)  // determine color
00407                                         {
00408                                                 if (!drawBackground_)
00409                                                 {
00410                                                         factor[0] = factor[1] = factor[2] = 0;
00411                                                 }
00412                                                 else
00413                                                 {
00414                                                         factor[0] = Colors[colorCount][0];
00415                                                         factor[1] = Colors[colorCount][1];
00416                                                         factor[2] = Colors[colorCount][2];
00417                                                 }
00418                                         }
00419                                         else
00420                                         {
00421                                                 //determine color for users
00422                                                 factor[0] = Colors[*pLabels % colorCount][0];
00423                                                 factor[1] = Colors[*pLabels % colorCount][1];
00424                                                 factor[2] = Colors[*pLabels % colorCount][2];
00425                                         }
00426 
00427                                         if(*pDepth != 0)
00428                                                 openni::CoordinateConverter::convertDepthToWorld(depthSensor_, (float)x, (float)y, (float)(*pDepth), &dX, &dY, &dZ);
00429                                         else
00430                                                 dX = dY = dZ = 0.f;
00431                                         pcl::PointXYZRGB& point = pcl_cloud_->at(x,y);
00432                                         point.r = 255*factor[0];
00433                                         point.g = 255*factor[1];
00434                                         point.b = 255*factor[2];
00435 //                                      point.x = dZ/1000;              // todo: Kinect might be different from Asus?
00436 //                                      point.y = -dX/1000;
00437 //                                      point.z = dY/1000;
00438                                         point.x = dX/1000.0;
00439                                         point.y = -dY/1000.0;
00440                                         point.z = dZ/1000.0;
00441 
00442                                         if (*pDepth != 0)
00443                                         {
00444                                                 int nHistValue = m_pDepthHist[*pDepth];
00445                                                 pTex->r = nHistValue*factor[0];
00446                                                 pTex->g = nHistValue*factor[1];
00447                                                 pTex->b = nHistValue*factor[2];
00448 
00449                                                 factor[0] = factor[1] = factor[2] = 1;
00450                                         }
00451                                 }
00452                                 pDepthRow += rowSize;
00453                                 pTexRow += m_nTexMapX;
00454                         }
00455                 }
00456                 //publish pcl
00457                 drawPointCloud();
00458 
00459                 //go through possible users (all that have been detected)
00460                 const nite::Array<nite::UserData>& users = userTrackerFrame.getUsers();
00461                 for (int i = 0; i < users.getSize(); ++i)
00462                 {
00463                         const nite::UserData& user = users[i];
00464                         updateUserState(user, userTrackerFrame.getTimestamp());
00465 
00466                         if(user.isNew())
00467                         {
00468                                 m_pUserTracker->startSkeletonTracking(user.getId());
00469                                 m_pUserTracker->startPoseDetection(user.getId(), nite::POSE_CROSSED_HANDS);
00470                         }
00471                         else if(!user.isLost() && users[i].getSkeleton().getState() == nite::SKELETON_TRACKED)
00472                         {
00473                                 if (drawSkeleton_)
00474                                         drawSkeleton(m_pUserTracker, user);
00475 
00476                                 if(drawFrames_)
00477                                 {
00478                                         drawFrames(user);
00479                                 }
00480 
00481                                 double length = sqrt(users[i].getCenterOfMass().x) + sqrt(users[i].getCenterOfMass().y) +
00482                                                 sqrt(users[i].getCenterOfMass().z);
00483                                 //if the user is valid (no empty information)
00484                                 if(length != 0)
00485                                 {
00486                                         //if the user in the list and valid, prepare list for update and
00487                                         //erase user
00488                                         bool found = false;
00489                                         for(std::list<nite::UserData>::iterator iter_ = tracked_users_->begin();
00490                                                         iter_ != tracked_users_->end(); ++iter_)
00491                                         {
00492                                                 if((*iter_).getId() == user.getId())
00493                                                 {
00494                                                         found = true;
00495                                                         tracked_users_->erase(iter_++);
00496                                                         //printf("erase: [");
00497                                                         //for (list<nite::UserData>::iterator iter =tracked_users_->begin();iter !=tracked_users_->end(); ++iter) {
00498                                                         //printf("%i ,", (unsigned int) (*iter).getId());
00499                                                         //}
00500                                                 }
00501                                         }
00502                                         //list waits for update
00503                                         if(found)
00504                                         {
00505                                                 //save updated data for a user in the list
00506                                                 tracked_users_->insert(tracked_users_->begin(), users[i]);
00507                                         }
00508                                         //if the user is valid and has not been in the list jet,
00509                                         //insert the user to the list
00510                                         if(!found || tracked_users_->empty())
00511                                         {
00512                                                 tracked_users_->insert(tracked_users_->end(), users[i]);
00513                                         }
00514                                 }
00515                         }
00516                         else if(user.isLost())
00517                         {
00518                                 //delete user out of the list
00519                                 for(std::list<nite::UserData>::iterator iter_ = tracked_users_->begin();
00520                                                 iter_ != tracked_users_->end(); ++iter_)
00521                                 {
00522                                         if((*iter_).getId() ==  user.getId())
00523                                                 tracked_users_->erase(iter_++);
00524                                 }
00525                         }
00526 
00527                         if (m_poseUser == 0 || m_poseUser == user.getId())
00528                         {
00529                                 const nite::PoseData& pose = user.getPose(nite::POSE_CROSSED_HANDS);
00530                                 if (pose.isEntered())
00531                                 {
00532                                         // Start timer
00533                                         sprintf(generalMessage, "In exit pose. Keep it for %d second%s to exit\n", poseTimeoutToExit_/1000, poseTimeoutToExit_/1000 == 1 ? "" : "s");
00534                                         printf("Waiting to start timeout %i \n", poseTimeoutToExit_/1000);
00535                                         m_poseUser = user.getId();
00536                                         m_poseTime_ = userTrackerFrame.getTimestamp();
00537                                 }
00538                                 else if (pose.isExited())
00539                                 {
00540                                         memset(generalMessage, 0, sizeof(generalMessage));
00541                                         m_poseTime_ = 0;
00542                                         m_poseUser = 0;
00543                                 }
00544                                 else if (pose.isHeld())
00545                                 {
00546                                         if (userTrackerFrame.getTimestamp() - m_poseTime_ > poseTimeoutToExit_ * 1000)
00547                                         {
00548                                                 printf("Timeout.");
00549                                         }
00550                                 }
00551                         }
00552                 }
00553                 publishTrackedUserMsg();
00554         }
00555 }
00556 /*
00557  * Publishes user message [@cob_perception_msgs::Person] on the given topic of [@people_pub] publisher.
00558  */
00559 void BodyTracker::publishTrackedUserMsg()
00560 {
00561         //publish tracked users
00562         std::vector<cob_perception_msgs::Person> detected_people;
00563         for(std::list<nite::UserData>::iterator iter_ = tracked_users_->begin(); iter_ != tracked_users_->end(); ++iter_)
00564         {
00565                 cob_perception_msgs::Person person;
00566                 cob_perception_msgs::Skeleton skeleton;
00567 
00568                 skeleton.joints.push_back(convertNiteJointToMsgs((*iter_).getSkeleton().getJoint(nite::JOINT_HEAD)));
00569                 skeleton.joints.push_back(convertNiteJointToMsgs((*iter_).getSkeleton().getJoint(nite::JOINT_NECK)));
00570                 skeleton.joints.push_back(convertNiteJointToMsgs((*iter_).getSkeleton().getJoint(nite::JOINT_LEFT_SHOULDER)));
00571                 skeleton.joints.push_back(convertNiteJointToMsgs((*iter_).getSkeleton().getJoint(nite::JOINT_RIGHT_SHOULDER)));
00572                 skeleton.joints.push_back(convertNiteJointToMsgs((*iter_).getSkeleton().getJoint(nite::JOINT_LEFT_ELBOW)));
00573                 skeleton.joints.push_back(convertNiteJointToMsgs((*iter_).getSkeleton().getJoint(nite::JOINT_RIGHT_ELBOW)));
00574                 skeleton.joints.push_back(convertNiteJointToMsgs((*iter_).getSkeleton().getJoint(nite::JOINT_LEFT_HAND)));
00575                 skeleton.joints.push_back(convertNiteJointToMsgs((*iter_).getSkeleton().getJoint(nite::JOINT_RIGHT_HAND)));
00576                 skeleton.joints.push_back(convertNiteJointToMsgs((*iter_).getSkeleton().getJoint(nite::JOINT_TORSO)));
00577                 skeleton.joints.push_back(convertNiteJointToMsgs((*iter_).getSkeleton().getJoint(nite::JOINT_LEFT_HIP)));
00578                 skeleton.joints.push_back(convertNiteJointToMsgs((*iter_).getSkeleton().getJoint(nite::JOINT_RIGHT_HIP)));
00579                 skeleton.joints.push_back(convertNiteJointToMsgs((*iter_).getSkeleton().getJoint(nite::JOINT_LEFT_KNEE)));
00580                 skeleton.joints.push_back(convertNiteJointToMsgs((*iter_).getSkeleton().getJoint(nite::JOINT_RIGHT_KNEE)));
00581                 skeleton.joints.push_back(convertNiteJointToMsgs((*iter_).getSkeleton().getJoint(nite::JOINT_LEFT_FOOT)));
00582                 skeleton.joints.push_back(convertNiteJointToMsgs((*iter_).getSkeleton().getJoint(nite::JOINT_RIGHT_FOOT)));
00583 
00584                 char id[100];
00585                 snprintf(id,100,"person %d", (*iter_).getId());
00586                 string id_ = std::string(id);
00587 
00588                 person.name = id_;
00589                 person.detector = detector_;
00590                 person.position.position.x = (*iter_).getCenterOfMass().x/1000.0;
00591                 person.position.position.y = -(*iter_).getCenterOfMass().y/1000.0;
00592                 person.position.position.z = (*iter_).getCenterOfMass().z/1000.0;
00593 
00594                 person.skeleton = skeleton;
00595 
00596                 unsigned int length = sqrt(person.position.position.x) + sqrt(person.position.position.y) +
00597                                 sqrt(person.position.position.z);
00598 
00599                 //save only valid data and no empty points
00600                 if(length != 0)
00601                         detected_people.push_back(person);
00602         }
00603         cob_perception_msgs::People array;
00604         array.header.stamp = ros::Time::now();
00605         array.header.frame_id = depth_optical_frame_;
00606         array.people = detected_people;
00607         people_pub_.publish(array);
00608 
00609 }
00610 /*
00611  * Updates and prints the user information.
00612  */
00613 void BodyTracker::updateUserState(const nite::UserData& user, uint64_t ts)
00614 {
00615         if(user.isNew()){
00616                 USER_MESSAGE("New User detected.");
00617         }
00618         else if(user.isVisible() && !visibleUsers[user.getId()]){
00619                 printf("[%08" PRIu64 "] User #%d:\tVisible\n", ts, user.getId());
00620         }
00621         else if(!user.isVisible() && visibleUsers[user.getId()]){
00622                 printf("[%08" PRIu64 "] User #%d:\tOut of Scene\n", ts, user.getId());
00623         }
00624         else if(user.isLost()){
00625                 USER_MESSAGE("Lost");
00626         }
00627         visibleUsers[user.getId()] = user.isVisible();
00628 
00629         if(skeletonStates[user.getId()] != user.getSkeleton().getState())
00630         {
00631                 switch(skeletonStates[user.getId()] = user.getSkeleton().getState())
00632                 {
00633                 case nite::SKELETON_NONE:
00634                         USER_MESSAGE("Stopped tracking !")
00635                         break;
00636                 case nite::SKELETON_CALIBRATING:
00637                         USER_MESSAGE("Calibrating...")
00638                         break;
00639                 case nite::SKELETON_TRACKED:
00640                         USER_MESSAGE("Tracking ...");
00641                         break;
00642                 case nite::SKELETON_CALIBRATION_ERROR_NOT_IN_POSE:
00643                 case nite::SKELETON_CALIBRATION_ERROR_HANDS:
00644                 case nite::SKELETON_CALIBRATION_ERROR_LEGS:
00645                 case nite::SKELETON_CALIBRATION_ERROR_HEAD:
00646                 case nite::SKELETON_CALIBRATION_ERROR_TORSO:
00647                         USER_MESSAGE("Calibration Failed... :-|")
00648                         break;
00649                 }
00650         }
00651 }
00652 
00653 /*
00654  * Publishes joints on TF.
00655  */
00656 void BodyTracker::publishJoints(ros::NodeHandle& nh, tf::TransformBroadcaster& br, std::string joint_name,
00657                 nite::SkeletonJoint joint, std::string tf_prefix, std::string rel_frame, int id){
00658 
00659         if (joint.getPositionConfidence() > 0.0)
00660         {
00661                 tf::Transform transform;
00662                 transform.setOrigin(tf::Vector3(joint.getPosition().x/1000.0, -joint.getPosition().y/1000.0,
00663                                 joint.getPosition().z/1000.0));
00664                 tf::Quaternion frame_rotation;
00665                 frame_rotation.setEuler(0, 0, 0);
00666                 transform.setRotation(frame_rotation);
00667                 std::stringstream frame_id_stream;
00668                 std::string frame_id;
00669                 frame_id_stream << "/" << tf_prefix << "/user_" << id << "/" << joint_name;
00670                 //frame_id_stream << "user_" << id << "-" << joint_name;
00671                 frame_id = frame_id_stream.str();
00672                 // std::cout << frame_id << std::endl;
00673                 br.sendTransform(tf::StampedTransform(transform, ros::Time::now(), rel_frame, frame_id));
00674         }
00675 }
00676 
00677 /*
00678  * Converts a nite message to a geometry message.
00679  */
00680 geometry_msgs::Pose BodyTracker::convertNiteJointToMsgs(nite::SkeletonJoint joint)
00681 {
00682         geometry_msgs::Pose transform_msgs;
00683 
00684         if (joint.getPositionConfidence() > 0.0)
00685         {
00686                 tf::Transform transform;
00687                 transform.setOrigin(tf::Vector3(joint.getPosition().x/1000.0, -joint.getPosition().y/1000.0,
00688                                 joint.getPosition().z/1000.0));
00689                 tf::Quaternion frame_rotation;
00690                 frame_rotation.setEuler(0, 0, 0);
00691                 transform.setRotation(frame_rotation);
00692                 tf::poseTFToMsg(transform, transform_msgs);
00693         }
00694         return transform_msgs;
00695 }
00696 
00697 /*
00698  * Draws a Point Cloud. Resets the points of a [@pcl_cloud].
00699  */
00700 void BodyTracker::drawPointCloud()
00701 {
00702         sensor_msgs::PointCloud2 pc;
00703         pcl::toROSMsg(*pcl_cloud_, pc);
00704 
00705         ros::Time time = ros::Time::now();
00706         //uint64_t st = time.toNSec();
00707         pc.header.stamp = time;
00708         pc.header.frame_id = depth_optical_frame_;
00709 
00710         pcl_pub_.publish(pc);
00711         pcl_cloud_->points.clear();
00712 }
00713 /*
00714  * Draws the limbs of a person on an image view.
00715  */
00716 void BodyTracker::drawLimb(nite::UserTracker* pUserTracker, const nite::SkeletonJoint& joint1, const nite::SkeletonJoint& joint2, int color)
00717 {
00718         //TO DO: compose limbs for drawing function
00719 }
00720 /*
00721  * Draws a skeleton on an image view.
00722  */
00723 void BodyTracker::drawSkeleton(nite::UserTracker* pUserTracker, const nite::UserData& userData)
00724 {
00725         //TO DO: draw skeleton on image view
00726         drawLimb(pUserTracker, userData.getSkeleton().getJoint(nite::JOINT_HEAD), userData.getSkeleton().getJoint(nite::JOINT_NECK), userData.getId() % colorCount);
00727         drawLimb(pUserTracker, userData.getSkeleton().getJoint(nite::JOINT_LEFT_SHOULDER), userData.getSkeleton().getJoint(nite::JOINT_LEFT_ELBOW), userData.getId() % colorCount);
00728         drawLimb(pUserTracker, userData.getSkeleton().getJoint(nite::JOINT_LEFT_ELBOW), userData.getSkeleton().getJoint(nite::JOINT_LEFT_HAND), userData.getId() % colorCount);
00729         drawLimb(pUserTracker, userData.getSkeleton().getJoint(nite::JOINT_RIGHT_SHOULDER), userData.getSkeleton().getJoint(nite::JOINT_RIGHT_ELBOW), userData.getId() % colorCount);
00730         drawLimb(pUserTracker, userData.getSkeleton().getJoint(nite::JOINT_RIGHT_ELBOW), userData.getSkeleton().getJoint(nite::JOINT_RIGHT_HAND), userData.getId() % colorCount);
00731         drawLimb(pUserTracker, userData.getSkeleton().getJoint(nite::JOINT_LEFT_SHOULDER), userData.getSkeleton().getJoint(nite::JOINT_RIGHT_SHOULDER), userData.getId() % colorCount);
00732         drawLimb(pUserTracker, userData.getSkeleton().getJoint(nite::JOINT_LEFT_SHOULDER), userData.getSkeleton().getJoint(nite::JOINT_TORSO), userData.getId() % colorCount);
00733         drawLimb(pUserTracker, userData.getSkeleton().getJoint(nite::JOINT_RIGHT_SHOULDER), userData.getSkeleton().getJoint(nite::JOINT_TORSO), userData.getId() % colorCount);
00734         drawLimb(pUserTracker, userData.getSkeleton().getJoint(nite::JOINT_TORSO), userData.getSkeleton().getJoint(nite::JOINT_LEFT_HIP), userData.getId() % colorCount);
00735         drawLimb(pUserTracker, userData.getSkeleton().getJoint(nite::JOINT_TORSO), userData.getSkeleton().getJoint(nite::JOINT_RIGHT_HIP), userData.getId() % colorCount);
00736         drawLimb(pUserTracker, userData.getSkeleton().getJoint(nite::JOINT_LEFT_HIP), userData.getSkeleton().getJoint(nite::JOINT_RIGHT_HIP), userData.getId() % colorCount);
00737         drawLimb(pUserTracker, userData.getSkeleton().getJoint(nite::JOINT_LEFT_HIP), userData.getSkeleton().getJoint(nite::JOINT_LEFT_KNEE), userData.getId() % colorCount);
00738         drawLimb(pUserTracker, userData.getSkeleton().getJoint(nite::JOINT_LEFT_KNEE), userData.getSkeleton().getJoint(nite::JOINT_LEFT_FOOT), userData.getId() % colorCount);
00739         drawLimb(pUserTracker, userData.getSkeleton().getJoint(nite::JOINT_RIGHT_HIP), userData.getSkeleton().getJoint(nite::JOINT_RIGHT_KNEE), userData.getId() % colorCount);
00740         drawLimb(pUserTracker, userData.getSkeleton().getJoint(nite::JOINT_RIGHT_KNEE), userData.getSkeleton().getJoint(nite::JOINT_RIGHT_FOOT), userData.getId() % colorCount);
00741 }
00742 
00743 /*
00744  * Writes down a label on an image view
00745  */
00746 void BodyTracker::drawUserName(const nite::UserData& user, cv::Mat& color_image, cv::Point& tag_coords)
00747 {
00748         //
00749         //      std::string tag_label = "User" + user.getId();
00750         //      std::cout << "The text tag reads: " << tag_label << "." << std::endl;
00751         //      cv::putText(color_image, tag_label, tag_coords, cv::FONT_HERSHEY_PLAIN, 3, CV_RGB(0,0,255), 2);
00752 
00753         //TO DO: write down a label on image view
00754 
00755 }
00756 /*
00757  * Publishes frames and joints markers on TF.
00758  */
00759 void BodyTracker::drawFrames(const nite::UserData& user)
00760 {
00761         int r = 255*Colors[user.getId() % colorCount][0];
00762         int g = 255*Colors[user.getId() % colorCount][1];
00763         int b = 255*Colors[user.getId() % colorCount][2];
00764 
00765         JointMap joints;
00766         joints["head"] = (user.getSkeleton().getJoint(nite::JOINT_HEAD));
00767         joints["neck"] = (user.getSkeleton().getJoint(nite::JOINT_NECK));
00768         joints["left_shoulder"] = (user.getSkeleton().getJoint(nite::JOINT_LEFT_SHOULDER));
00769         joints["right_shoulder"] = (user.getSkeleton().getJoint(nite::JOINT_RIGHT_SHOULDER));
00770         joints["left_elbow"] = (user.getSkeleton().getJoint(nite::JOINT_LEFT_ELBOW));
00771         joints["right_elbow"] = (user.getSkeleton().getJoint(nite::JOINT_RIGHT_ELBOW));
00772         joints["left_hand"] = (user.getSkeleton().getJoint(nite::JOINT_LEFT_HAND));
00773         joints["right_hand"] = (user.getSkeleton().getJoint(nite::JOINT_RIGHT_HAND));
00774         joints["torso"] = (user.getSkeleton().getJoint(nite::JOINT_TORSO));
00775         joints["left_hip"] = (user.getSkeleton().getJoint(nite::JOINT_LEFT_HIP));
00776         joints["right_hip"] = (user.getSkeleton().getJoint(nite::JOINT_RIGHT_HIP));
00777         joints["left_knee"] = (user.getSkeleton().getJoint(nite::JOINT_LEFT_KNEE));
00778         joints["right_knee"] = (user.getSkeleton().getJoint(nite::JOINT_RIGHT_KNEE));
00779         joints["left_foot"] = (user.getSkeleton().getJoint(nite::JOINT_LEFT_FOOT));
00780         joints["right_foot"] = (user.getSkeleton().getJoint(nite::JOINT_RIGHT_FOOT));
00781 
00782         for (JointMap::iterator it=joints.begin(); it!=joints.end(); ++it){
00783                 publishJoints(nh_, transform_broadcaster_, it->first, it->second, tf_prefix_, depth_optical_frame_, user.getId());
00784         }
00785 
00786         drawCircle(r, g, b, joints["head"].getPosition());
00787         drawCircle(r, g, b, joints["right_hand"].getPosition());
00788         drawCircle(r, g, b, joints["left_hand"].getPosition());
00789         drawCircle(r, g, b, joints["right_foot"].getPosition());
00790         drawCircle(r, g, b, joints["left_foot"].getPosition());
00791 
00792         drawLine(r, g, b, joints["head"].getPosition(), joints["neck"].getPosition());
00793         drawLine(r, g, b, joints["neck"].getPosition(), joints["left_shoulder"].getPosition());
00794         drawLine(r, g, b, joints["neck"].getPosition(), joints["right_shoulder"].getPosition());
00795         drawLine(r, g, b, joints["right_shoulder"].getPosition(), joints["right_elbow"].getPosition());
00796         drawLine(r, g, b, joints["left_shoulder"].getPosition(), joints["left_elbow"].getPosition());
00797         drawLine(r, g, b, joints["right_elbow"].getPosition(), joints["right_hand"].getPosition());
00798         drawLine(r, g, b, joints["left_elbow"].getPosition(), joints["left_hand"].getPosition());
00799         drawLine(r, g, b, joints["neck"].getPosition(), joints["torso"].getPosition());
00800         drawLine(r, g, b, joints["torso"].getPosition(), joints["left_hip"].getPosition());
00801         drawLine(r, g, b, joints["torso"].getPosition(), joints["right_hip"].getPosition());
00802         drawLine(r, g, b, joints["right_hip"].getPosition(), joints["right_knee"].getPosition());
00803         drawLine(r, g, b, joints["left_hip"].getPosition(), joints["left_knee"].getPosition());
00804         drawLine(r, g, b, joints["right_knee"].getPosition(), joints["right_foot"].getPosition());
00805         drawLine(r, g, b, joints["left_knee"].getPosition(), joints["left_foot"].getPosition());
00806 
00807 }
00808 
00812 void BodyTracker::drawLine (const double r, const double g, const double b,
00813                 const nite::Point3f& pose_start, const nite::Point3f& pose_end )
00814 {
00815         visualization_msgs::Marker marker;
00816         marker.header.frame_id = depth_optical_frame_;
00817         marker.header.stamp = ros::Time::now();
00818         marker.action = visualization_msgs::Marker::ADD;
00819         marker.type = visualization_msgs::Marker::LINE_STRIP;
00820         geometry_msgs::Point p;
00821         marker.id = marker_id_;
00822         p.x = pose_start.x/1000.0;
00823         p.y = -pose_start.y/1000.0;
00824         p.z = pose_start.z/1000.0;
00825         marker.points.push_back(p);
00826         p.x =pose_end.x/1000.0;
00827         p.y = pose_end.y/1000.0;
00828         p.z = pose_end.z/1000.0;
00829         marker.points.push_back(p);
00830         marker.scale.x = 0.019;
00831         marker.scale.y = 0.0;
00832         marker.scale.z = 0.0;
00833         marker.color.r = r;
00834         marker.color.g = g;
00835         marker.color.b = b;
00836         marker.lifetime = ros::Duration(0.01);
00837         vis_pub_.publish(marker);
00838         marker_id_++;
00839 }
00840 
00841 /*
00842  * A helper function to draw circles in rviz
00843  */
00844 
00845 void BodyTracker::drawCircle(const double r, const double g, const double b,
00846                 const nite::Point3f& pose){
00847         visualization_msgs::Marker m;
00848         m.header.stamp = ros::Time::now();
00849         m.action = visualization_msgs::Marker::ADD;
00850         m.header.frame_id = "/camra_link";
00851         m.type = m.SPHERE;
00852         m.id = marker_id_;
00853         m.pose.position.x = pose.x/1000.0;
00854         m.pose.position.y = -pose.y/1000.0;
00855         m.pose.position.z = pose.z/1000.0;
00856         m.scale.x = .1;
00857         m.scale.y = .1;
00858         m.scale.z = .1;
00859         m.color.r = 1;
00860         m.lifetime = ros::Duration(0.01);
00861         vis_pub_.publish(m);
00862         marker_id_++;
00863 }
00864 
00865 void BodyTracker::calculateHistogram(float* pHistogram, int histogramSize, const openni::VideoFrameRef& depthFrame)
00866 {
00867         const openni::DepthPixel* pDepth = (const openni::DepthPixel*)depthFrame.getData();
00868         int width = depthFrame.getWidth();
00869         int height = depthFrame.getHeight();
00870         // Calculate the accumulative histogram (the yellow display...)
00871         memset(pHistogram, 0, histogramSize*sizeof(float));
00872         int restOfRow = depthFrame.getStrideInBytes() / sizeof(openni::DepthPixel) - width;
00873 
00874         unsigned int nNumberOfPoints = 0;
00875         for (int y = 0; y < height; ++y)
00876         {
00877                 for (int x = 0; x < width; ++x, ++pDepth)
00878                 {
00879                         if (*pDepth != 0)
00880                         {
00881                                 pHistogram[*pDepth]++;
00882                                 nNumberOfPoints++;
00883                         }
00884                 }
00885                 pDepth += restOfRow;
00886         }
00887         for (int nIndex=1; nIndex<histogramSize; nIndex++)
00888         {
00889                 pHistogram[nIndex] += pHistogram[nIndex-1];
00890         }
00891         if (nNumberOfPoints)
00892         {
00893                 for (int nIndex=1; nIndex<histogramSize; nIndex++)
00894                 {
00895                         pHistogram[nIndex] = (256 * (1.0f - (pHistogram[nIndex] / nNumberOfPoints)));
00896                 }
00897         }
00898 }
00899 
00900 int main(int argc, char** argv)
00901 {
00902         ros::init(argc, argv, "cob_body_tracker");
00903         ros::NodeHandle nh_priv("~");
00904         BodyTracker BodyTracker(nh_priv);
00905 
00906         ros::spin();
00907         return 0;
00908 
00909 }


cob_openni2_tracker
Author(s): Marcus Liebhardt , Olha Meyer
autogenerated on Mon May 6 2019 02:32:19