Go to the documentation of this file.00001 #include "iri_people_tracking_alg_node.h"
00002
00003 IriPeopleTrackingAlgNode::IriPeopleTrackingAlgNode(void) :
00004 people_tracking_aserver_(public_node_handle_, "people_tracking")
00005 {
00006
00007 this->loop_rate_ = 30;
00008
00009
00010
00011
00012
00013
00014
00015 this->peopleSet_publisher_ = this->public_node_handle_.advertise<iri_perception_msgs::peopleTrackingArray>("peopleSet", 100);
00016 this->particleSet_publisher_ = this->public_node_handle_.advertise<visualization_msgs::MarkerArray>("particleSet", 100);
00017
00018
00019 people_detection_subscriber_ = public_node_handle_.subscribe("people_detection", 100, &IriPeopleTrackingAlgNode::people_detection_callback, this);
00020 platformOdometry_subscriber_ = public_node_handle_.subscribe("odom", 100, &IriPeopleTrackingAlgNode::platformOdometry_callback, this);
00021
00022
00023
00024
00025
00026
00027 people_tracking_aserver_.registerStartCallback(boost::bind(&IriPeopleTrackingAlgNode::people_trackingStartCallback, this, _1));
00028 people_tracking_aserver_.registerStopCallback(boost::bind(&IriPeopleTrackingAlgNode::people_trackingStopCallback, this));
00029 people_tracking_aserver_.registerIsFinishedCallback(boost::bind(&IriPeopleTrackingAlgNode::people_trackingIsFinishedCallback, this));
00030 people_tracking_aserver_.registerHasSucceedCallback(boost::bind(&IriPeopleTrackingAlgNode::people_trackingHasSucceedCallback, this));
00031 people_tracking_aserver_.registerGetResultCallback(boost::bind(&IriPeopleTrackingAlgNode::people_trackingGetResultCallback, this, _1));
00032 people_tracking_aserver_.registerGetFeedbackCallback(boost::bind(&IriPeopleTrackingAlgNode::people_trackingGetFeedbackCallback, this, _1));
00033 people_tracking_aserver_.start();
00034
00035
00036 }
00037
00038 IriPeopleTrackingAlgNode::~IriPeopleTrackingAlgNode(void)
00039 {
00040
00041 }
00042
00043 void IriPeopleTrackingAlgNode::fillTopicMsgs(std::list<CpeopleTrackingObservation> & peopleList)
00044 {
00045 alg_.lock();
00046 this->peopleTrackingArray_msg_.peopleSet.clear();
00047 this->peopleTrackingArray_msg_.peopleSet.resize(peopleList.size());
00048 this->MarkerArray_msg_.markers.clear();
00049 static unsigned int lastSize=0;
00050 this->MarkerArray_msg_.markers.resize(std::max(uint(peopleList.size()), lastSize));
00051 lastSize = peopleList.size();
00052
00053
00054 peopleTrackingArray_msg_.header.seq++;
00055 people_detection_mutex_.enter();
00056 peopleTrackingArray_msg_.header.frame_id = people_detector_frame_id_;
00057 peopleTrackingArray_msg_.header.stamp = people_detector_stamp_;
00058 people_detection_mutex_.exit();
00059
00060 unsigned int ii = 0;
00061 for (std::list<CpeopleTrackingObservation>::iterator iiP=peopleList.begin();
00062 iiP!=peopleList.end(); iiP++,ii++)
00063 {
00064
00065 this->peopleTrackingArray_msg_.peopleSet[ii].targetId = iiP->id;
00066 this->peopleTrackingArray_msg_.peopleSet[ii].x = iiP->point.getX();
00067 this->peopleTrackingArray_msg_.peopleSet[ii].y = iiP->point.getY();
00068 this->peopleTrackingArray_msg_.peopleSet[ii].vx = iiP->velocities.getX();
00069 this->peopleTrackingArray_msg_.peopleSet[ii].vy = iiP->velocities.getY();
00070 this->peopleTrackingArray_msg_.peopleSet[ii].covariances[0] = iiP->point.getCxx();
00071 this->peopleTrackingArray_msg_.peopleSet[ii].covariances[1] = iiP->point.getCxy();
00072
00073
00074 this->peopleTrackingArray_msg_.peopleSet[ii].covariances[4] = iiP->point.getCxy();
00075 this->peopleTrackingArray_msg_.peopleSet[ii].covariances[5] = iiP->point.getCyy();
00076
00077
00078
00079
00080
00081
00082
00083
00084
00085
00086
00087
00088 this->MarkerArray_msg_.markers[ii].header = this->peopleTrackingArray_msg_.header;
00089 this->MarkerArray_msg_.markers[ii].id = iiP->id;
00090
00091 this->MarkerArray_msg_.markers[ii].type = visualization_msgs::Marker::TEXT_VIEW_FACING;
00092 this->MarkerArray_msg_.markers[ii].action = visualization_msgs::Marker::ADD;
00093
00094 this->MarkerArray_msg_.markers[ii].pose.position.x = iiP->point.getX();
00095 this->MarkerArray_msg_.markers[ii].pose.position.y = iiP->point.getY();
00096 this->MarkerArray_msg_.markers[ii].pose.position.z = 0.2;
00097
00098
00099 double headingAngle = iiP->heading;
00100 geometry_msgs::Quaternion headingQuaternion = tf::createQuaternionMsgFromYaw(headingAngle);
00101 this->MarkerArray_msg_.markers[ii].pose.orientation.x = headingQuaternion.x;
00102 this->MarkerArray_msg_.markers[ii].pose.orientation.y = headingQuaternion.y;
00103 this->MarkerArray_msg_.markers[ii].pose.orientation.z = headingQuaternion.z;
00104 this->MarkerArray_msg_.markers[ii].pose.orientation.w = headingQuaternion.w;
00105
00106
00107
00108 this->MarkerArray_msg_.markers[ii].scale.x = markerSize/2.0;
00109 this->MarkerArray_msg_.markers[ii].scale.y = markerSize*3.0;
00110 this->MarkerArray_msg_.markers[ii].scale.z = markerSize/2.0;
00111 this->MarkerArray_msg_.markers[ii].color.a = 1.0;
00112 this->MarkerArray_msg_.markers[ii].color.r = 0.02*iiP->id*markerR - int(0.02*iiP->id*markerR) ;
00113 this->MarkerArray_msg_.markers[ii].color.g = 0.04*iiP->id*markerG - int(0.04*iiP->id*markerG) ;
00114 this->MarkerArray_msg_.markers[ii].color.b = 0.06*iiP->id*markerB - int(0.06*iiP->id*markerB) ;
00115 this->MarkerArray_msg_.markers[ii].lifetime = ros::Duration(1.0f);
00116
00117
00118 std::stringstream idtracker;
00119 idtracker << iiP->id ;
00120 this->MarkerArray_msg_.markers[ii].text = idtracker.str();
00121
00122
00123 }
00124
00125
00126 for(unsigned int i=peopleList.size(); i<this->MarkerArray_msg_.markers.size(); i++)
00127 {
00128 this->MarkerArray_msg_.markers[i].header = this->peopleTrackingArray_msg_.header;
00129 this->MarkerArray_msg_.markers[i].action = visualization_msgs::Marker::DELETE;
00130 }
00131 alg_.unlock();
00132 }
00133
00134 void IriPeopleTrackingAlgNode::mainNodeThread(void)
00135 {
00136 people_detection_mutex_.enter();
00137
00138 std::cout << "Detection Set:"; tracker.printDetectionSet();
00139
00140
00141 platformOdometry_mutex_.enter();
00142 tracker.propagateFilters(odometry);
00143 platformOdometry_mutex_.exit();
00144
00145 tracker.propagateFilters();
00146
00147
00148
00149 tracker.negotiateNewFilters();
00150 tracker.correctFilters();
00151 std::cout << "Posterior People Set: "; tracker.printPeopleSet();
00152 tracker.negotiateDeleteFilters();
00153
00154
00155 std::list<CpeopleTrackingObservation> peopleList;
00156 tracker.getTrackingResult(peopleList);
00157 tracker.resampleFilters();
00158 std::cout << "*********************************" << std::endl;
00159 people_detection_mutex_.exit();
00160
00161
00162 fillTopicMsgs(peopleList);
00163
00164
00165
00166
00167
00168
00169 peopleSet_publisher_.publish(peopleTrackingArray_msg_);
00170 particleSet_publisher_.publish(MarkerArray_msg_);
00171 }
00172
00173
00174 void IriPeopleTrackingAlgNode::people_detection_callback(const iri_perception_msgs::detectionArray::ConstPtr& msg)
00175 {
00176
00177
00178 people_detection_mutex_.enter();
00179
00180 tracker.resetDetectionSet();
00181
00182 people_detector_frame_id_ = msg->header.frame_id;
00183 people_detector_stamp_ = msg->header.stamp;
00184
00185
00186 for (unsigned int ii=0; ii<msg->detection.size(); ii++)
00187 {
00188 CpeopleDetectionObservation newDetection;
00189 newDetection.point.setXY(msg->detection[ii].position.x, msg->detection[ii].position.y);
00190 newDetection.point.setCov(DEFAULT_DET_COV_XY,DEFAULT_DET_COV_XY,0.0);
00191 tracker.addDetection(newDetection);
00192 }
00193
00194
00195 people_detection_mutex_.exit();
00196 }
00197
00198 void IriPeopleTrackingAlgNode::platformOdometry_callback(const nav_msgs::Odometry::ConstPtr& msg)
00199 {
00200 double vx,vy,vz,vTrans;
00201 double tLast, dT;
00202
00203
00204
00205
00206
00207 this->platformOdometry_mutex_.enter();
00208
00209
00210 tLast = odometry.getTimeStamp();
00211 odometry.setTimeStamp();
00212 dT = odometry.getTimeStamp() - tLast;
00213 vx = msg->twist.twist.linear.x;
00214 vy = msg->twist.twist.linear.y;
00215 vz = msg->twist.twist.linear.z;
00216 vTrans = sqrt(vx*vx+vy*vy+vz*vz);
00217 odometry.acumulateToDeltas( dT*vTrans , dT*msg->twist.twist.angular.z );
00218
00219
00220
00221 this->platformOdometry_mutex_.exit();
00222 }
00223
00224
00225
00226
00227 void IriPeopleTrackingAlgNode::people_trackingStartCallback(const iri_perception_msgs::peopleTrackGoalConstPtr& goal)
00228 {
00229 alg_.lock();
00230
00231
00232 alg_.unlock();
00233 }
00234
00235 void IriPeopleTrackingAlgNode::people_trackingStopCallback(void)
00236 {
00237 alg_.lock();
00238
00239 alg_.unlock();
00240 }
00241
00242 bool IriPeopleTrackingAlgNode::people_trackingIsFinishedCallback(void)
00243 {
00244 bool ret = false;
00245
00246 alg_.lock();
00247 if(peopleTrackingArray_msg_.header.stamp != ros::Time(0))
00248 {
00249 ret = true;
00250 }
00251 alg_.unlock();
00252
00253 return ret;
00254 }
00255
00256 bool IriPeopleTrackingAlgNode::people_trackingHasSucceedCallback(void)
00257 {
00258 bool ret = true;
00259
00260 alg_.lock();
00261
00262
00263 alg_.unlock();
00264
00265 return ret;
00266 }
00267
00268 void IriPeopleTrackingAlgNode::people_trackingGetResultCallback(iri_perception_msgs::peopleTrackResultPtr& result)
00269 {
00270 alg_.lock();
00271
00272 result->ps.header = peopleTrackingArray_msg_.header;
00273 result->ps.peopleSet.resize(peopleTrackingArray_msg_.peopleSet.size());
00274 for(unsigned int ii=0; ii<peopleTrackingArray_msg_.peopleSet.size(); ii++)
00275 {
00276 result->ps.peopleSet[ii].targetId = peopleTrackingArray_msg_.peopleSet[ii].targetId;
00277 result->ps.peopleSet[ii].x = peopleTrackingArray_msg_.peopleSet[ii].x;
00278 result->ps.peopleSet[ii].y = peopleTrackingArray_msg_.peopleSet[ii].y;
00279 result->ps.peopleSet[ii].vx = peopleTrackingArray_msg_.peopleSet[ii].vx;
00280 result->ps.peopleSet[ii].vy = peopleTrackingArray_msg_.peopleSet[ii].vy;
00281 result->ps.peopleSet[ii].covariances = peopleTrackingArray_msg_.peopleSet[ii].covariances;
00282 }
00283 alg_.unlock();
00284 }
00285
00286 void IriPeopleTrackingAlgNode::people_trackingGetFeedbackCallback(iri_perception_msgs::peopleTrackFeedbackPtr& feedback)
00287 {
00288 alg_.lock();
00289
00290
00291 alg_.unlock();
00292 }
00293
00294
00295
00296 void IriPeopleTrackingAlgNode::node_config_update(Config &config, uint32_t level)
00297 {
00298 this->alg_.lock();
00299
00300 markerSize = config.markerSize;
00301 markerR = config.markerR;
00302 markerG = config.markerG;
00303 markerB = config.markerB;
00304
00305 this->alg_.config_ = config;
00306
00307 this->alg_.unlock();
00308 }
00309
00310 void IriPeopleTrackingAlgNode::addNodeDiagnostics(void)
00311 {
00312 }
00313
00314
00315 int main(int argc,char *argv[])
00316 {
00317 return algorithm_base::main<IriPeopleTrackingAlgNode>(argc, argv, "iri_people_tracking_alg_node");
00318 }