body_tracker.h
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 #ifndef _NITE_USER_VIEWER_H_
00069 #define _NITE_USER_VIEWER_H_
00070 
00071 //ROS includes
00072 #include <libnite2/NiTE.h>
00073 #include <ros/ros.h>
00074 #include <tf/tfMessage.h>
00075 #include <tf/transform_broadcaster.h>
00076 #include <tf/transform_listener.h>
00077 #include <tf/tf.h>
00078 //point cloud includes
00079 #include <pcl/ros/conversions.h>
00080 #include <pcl_ros/point_cloud.h>
00081 #include <pcl/point_types.h>
00082 //Messages
00083 #include <visualization_msgs/Marker.h>
00084 #include <cob_perception_msgs/Skeleton.h>
00085 #include <cob_perception_msgs/People.h>
00086 #include <sensor_msgs/image_encodings.h>
00087 #include <sensor_msgs/PointCloud2.h>
00088 //image and opencv
00089 #include <image_transport/image_transport.h>
00090 #include <image_transport/subscriber_filter.h>
00091 #include <opencv2/imgproc/imgproc.hpp>
00092 #include <opencv2/highgui/highgui.hpp>
00093 
00094 //#include <opencv/cv.h>
00095 //#include <opencv/highgui.h>
00096 #include <cv_bridge/cv_bridge.h>
00097 //boost
00098 #include <boost/thread/mutex.hpp>
00099 #include <boost/timer.hpp>
00100 //mathes
00101 #include <vector>
00102 
00103 #define MAX_DEPTH 10000
00104 typedef std::map<std::string, nite::SkeletonJoint>JointMap;
00105 
00106 class BodyTracker
00107 {
00108 
00109 public:
00110 
00111         BodyTracker(ros::NodeHandle nh);
00112         virtual ~BodyTracker();
00113         //PARAMS
00114         std::string tf_prefix_, rel_frame_, cam_frame_;
00115         openni::Device  device_;
00116         openni::VideoStream depthSensor_;
00117         void Finalize();
00118         void runTracker();
00119 
00120 private:
00121 
00122         //ROS ELEMENTS
00123         ros::NodeHandle nh_;
00124 
00125         //TF ELEMENTS
00126         tf::TransformListener transform_listener_;
00127         tf::TransformBroadcaster br_;
00128         ros::Publisher vis_pub_, pcl_pub_, skeleton_pub_, people_pub_;
00129         image_transport::ImageTransport* it_;
00130         image_transport::SubscriberFilter image_sub_;
00131         image_transport::SubscriberFilter pcl_sub_;
00132         image_transport::Publisher image_pub_;
00133         pcl::PointCloud<pcl::PointXYZRGB>::Ptr pcl_cloud_;
00134         void imgConnectCB(const image_transport::SingleSubscriberPublisher& pub);
00135         void imgDisconnectCB(const image_transport::SingleSubscriberPublisher& pub);
00136 
00137         std::list<nite::UserData>* tracked_users_;
00138 
00139         float m_pDepthHist[MAX_DEPTH];
00140         char m_strSampleName[ONI_MAX_STR];
00141 
00142         unsigned int m_nTexMapX;
00143         unsigned int m_nTexMapY;
00144 
00145         nite::UserTracker* m_pUserTracker;
00146         nite::UserId m_poseUser;
00147 
00148         openni::RGB888Pixel* m_pTexMap_;
00149 
00150         uint64_t m_poseTime_;
00151         unsigned int marker_id_;
00152         int poseTimeoutToExit_;
00153 
00154         bool drawSkeleton_;
00155         bool drawCenterOfMass_;
00156         bool drawUserName_;
00157         bool drawBoundingBox_;
00158         bool drawBackground_;
00159         bool drawDepth_;
00160         bool drawFrames_;
00161 
00162         BodyTracker(const BodyTracker&);
00163         BodyTracker& operator=(BodyTracker&);
00164 
00165         void init();
00166         void imageCallback(const sensor_msgs::ImageConstPtr& rgb_image_msg);
00167         void updateUserState(const nite::UserData& user, uint64_t ts);
00168         void publishJoints(ros::NodeHandle& nh, tf::TransformBroadcaster& br, std::string joint_name,
00169                         nite::SkeletonJoint joint, std::string tf_prefix, std::string rel_frame, int id);
00170         void publishTrackedUserMsg();
00171         void drawLine(const double r, const double g, const double b,
00172                         const nite::Point3f& pose_start, const nite::Point3f& pose_end );
00173         void drawCircle(const double r, const double g, const double b,
00174                         const nite::Point3f& pose);
00175         void drawSkeleton(nite::UserTracker* pUserTracker, const nite::UserData& userData);
00176         void drawUserName(const nite::UserData& user, cv::Mat& color_image, cv::Point& tag_coords);
00177         void drawFrames(const nite::UserData& user);
00178         void drawPointCloud();
00179         void drawLimb(nite::UserTracker* pUserTracker, const nite::SkeletonJoint& joint1, const nite::SkeletonJoint& joint2, int color);
00180         void calculateHistogram(float* pHistogram, int histogramSize, const openni::VideoFrameRef& depthFrame);
00181         void convertColorImageMsgToMat(const sensor_msgs::Image::ConstPtr& color_image_msg,
00182                         cv_bridge::CvImageConstPtr& color_image_ptr, cv::Mat& color_image);
00183         unsigned long convertColorImageMessageToMat(const sensor_msgs::Image::ConstPtr& color_image_msg,
00184                         cv_bridge::CvImageConstPtr& color_image_ptr, cv::Mat& color_image);
00185         geometry_msgs::Pose convertNiteJointToMsgs(nite::SkeletonJoint joint);
00186 
00187 };
00188 
00189 #endif // _NITE_USER_VIEWER_H_


cob_openni2_tracker
Author(s): Marcus Liebhardt , Olha Meyer
autogenerated on Fri Aug 28 2015 10:24:08