cluster.cpp
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
32 #include <mtt/cluster.h>
33 
35 {
36  id=0;
37 }
38 
40 {
41 // cout<<"deleted: "<<*this<<endl;
42 // assigned_measurements.clear();
43 // assigned_hypotheses.clear();
44 }
45 
47 {
48  if(assigned_hypotheses.size()==0)
49  return true;
50 
51  bool empty=true;
52 
53  for(uint i=0;i<assigned_hypotheses.size();i++)
54  if(assigned_hypotheses[i]->_status!=DEAD)
55  empty=false;
56 
57  if(empty)
58  return true;
59 
60  return false;
61 }
62 
63 ostream& operator<<(ostream& o, Cluster& c)
64 {
65  o<<"cluster: "<<c.id<<endl;
66 
67  o<<"\tmeasurements: "<<endl;
68 
69  if(c.assigned_measurements.size()==0)
70  o<<"\t\t[]"<<endl;
71 
72  for(uint i=0;i<c.assigned_measurements.size();++i)
73  o<<"\t\t"<<*(c.assigned_measurements[i])<<endl;
74 
75  o<<"\thypotheses: "<<endl;
76 
77  if(c.assigned_hypotheses.size()==0)
78  o<<"\t\t[]"<<endl;
79 
80  for(uint i=0;i<c.assigned_hypotheses.size();++i)
81  {
82  HypothesisPtr hypothesis = c.assigned_hypotheses[i];
83 
84  o<<"\t\t"<<hypothesis->_uid;
85 
86  switch(hypothesis->_status)
87  {
88  case DEAD:
89  o<<"D";
90  break;
91  case NORMAL:
92  o<<"N";
93  break;
94  case PARENT:
95  o<<"P";
96  break;
97  case FORCED_PARENT:
98  o<<"FP";
99  break;
100  case DEAD_FORCED_PARENT:
101  o<<"DFP";
102  break;
103  case ERROR:
104  o<<"E";
105  break;
106  }
107 
108  o<<" (";
109 
110  for(uint t=0;t<hypothesis->_targets.size();t++)
111  {
112  o<<hypothesis->_targets[t]->_id;
113  o<<" mi "<<hypothesis->_targets[t]->_missed_associations;
114 
115  if(t<hypothesis->_targets.size()-1)
116  o<<", ";
117  }
118 
119  o<<")"<<endl;
120 
121 // if(i<c.assigned_hypotheses.size()-1)
122 // o<<", ";
123  }
124 
125  return o;
126 }
127 
129 {
130  return c1->id<c2->id;
131 }
132 
133 ostream& operator<<(ostream& o,vector<ClusterPtr>& c)
134 {
135  for(uint i=0;i<c.size();i++)
136  {
137  o<<*c[i];
138  }
139  return o;
140 }
vector< MeasurementPtr > assigned_measurements
Measurements assigned to this cluster, these measurements are in conflict with the cluster targets...
Definition: cluster.h:61
vector< HypothesisPtr > assigned_hypotheses
Set of hypotheses belonging to the cluster.
Definition: cluster.h:63
boost::shared_ptr< Cluster > ClusterPtr
Shared pointer to the Cluster class.
Definition: cluster.h:85
long id
Id of the current cluster.
Definition: cluster.h:59
Cluster()
Cluster constructor, variable initialization.
Definition: cluster.cpp:34
bool compareClusters(ClusterPtr c1, ClusterPtr c2)
Compare two clusters.
Definition: cluster.cpp:128
~Cluster()
Cluster destructor, no task.
Definition: cluster.cpp:39
boost::shared_ptr< Hypothesis > HypothesisPtr
Definition: cluster.h:44
Timer t
Definition: k_best.cpp:34
bool isEmpty()
Check if the cluster is a candidate for deletion.
Definition: cluster.cpp:46
Hypotheses cluster class.
Definition: cluster.h:55
Hypotheses cluster definition.
ostream & operator<<(ostream &o, Cluster &c)
Definition: cluster.cpp:63


mtt
Author(s): Jorge Almeida
autogenerated on Mon Mar 2 2015 01:32:18