mcpdf_vector.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 /* Author: Wim Meeussen */
36 
39 #include <assert.h>
40 #include <vector>
41 #include <std_msgs/Float64.h>
43 
44 
45 using namespace MatrixWrapper;
46 using namespace BFL;
47 using namespace tf;
48 
49 static const unsigned int NUM_CONDARG = 1;
50 
51 
52 MCPdfVector::MCPdfVector(unsigned int num_samples)
53  : MCPdf<Vector3> (num_samples, NUM_CONDARG)
54 {}
55 
57 
58 
59 WeightedSample<Vector3>
60 MCPdfVector::SampleGet(unsigned int particle) const
61 {
62  assert((int)particle >= 0 && particle < _listOfSamples.size());
63  return _listOfSamples[particle];
64 }
65 
66 
68 {
69  Vector3 pos(0, 0, 0);
70  double current_weight;
71  std::vector<WeightedSample<Vector3> >::const_iterator it_los;
72  for (it_los = _listOfSamples.begin() ; it_los != _listOfSamples.end() ; it_los++)
73  {
74  current_weight = it_los->WeightGet();
75  pos += (it_los->ValueGet() * current_weight);
76  }
77 
78  return Vector3(pos);
79 }
80 
81 
83 void MCPdfVector::getParticleCloud(const Vector3& step, double threshold, sensor_msgs::PointCloud& cloud) const
84 {
85  unsigned int num_samples = _listOfSamples.size();
86  assert(num_samples > 0);
87  Vector3 m = _listOfSamples[0].ValueGet();
88  Vector3 M = _listOfSamples[0].ValueGet();
89 
90  // calculate min and max
91  for (unsigned int s = 0; s < num_samples; s++)
92  {
93  Vector3 v = _listOfSamples[s].ValueGet();
94  for (unsigned int i = 0; i < 3; i++)
95  {
96  if (v[i] < m[i]) m[i] = v[i];
97  if (v[i] > M[i]) M[i] = v[i];
98  }
99  }
100 
101  // get point cloud from histogram
102  Matrix hist = getHistogram(m, M, step);
103  unsigned int row = hist.rows();
104  unsigned int col = hist.columns();
105  unsigned int total = 0;
106  unsigned int t = 0;
107  for (unsigned int r = 1; r <= row; r++)
108  for (unsigned int c = 1; c <= col; c++)
109  if (hist(r, c) > threshold) total++;
110  cout << "size total " << total << endl;
111 
112  vector<geometry_msgs::Point32> points(total);
113  vector<float> weights(total);
114  sensor_msgs::ChannelFloat32 channel;
115  for (unsigned int r = 1; r <= row; r++)
116  for (unsigned int c = 1; c <= col; c++)
117  if (hist(r, c) > threshold)
118  {
119  for (unsigned int i = 0; i < 3; i++)
120  points[t].x = m[0] + (step[0] * r);
121  points[t].y = m[1] + (step[1] * c);
122  points[t].z = m[2];
123  weights[t] = rgb[999 - (int)trunc(max(0.0, min(999.0, hist(r, c) * 2 * total * total)))];
124  t++;
125  }
126  cout << "points size " << points.size() << endl;
127  cloud.header.frame_id = "base_link";
128  cloud.points = points;
129  channel.name = "rgb";
130  channel.values = weights;
131  cloud.channels.push_back(channel);
132 }
133 
134 
136 MatrixWrapper::Matrix MCPdfVector::getHistogram(const Vector3& m, const Vector3& M, const Vector3& step) const
137 {
138  unsigned int num_samples = _listOfSamples.size();
139  unsigned int rows = round((M[0] - m[0]) / step[0]);
140  unsigned int cols = round((M[1] - m[1]) / step[1]);
141  Matrix hist(rows, cols);
142  hist = 0;
143 
144  // calculate histogram
145  for (unsigned int i = 0; i < num_samples; i++)
146  {
147  Vector3 rel(_listOfSamples[i].ValueGet() - m);
148  unsigned int r = round(rel[0] / step[0]);
149  unsigned int c = round(rel[1] / step[1]);
150  if (r >= 1 && c >= 1 && r <= rows && c <= cols)
151  hist(r, c) += _listOfSamples[i].WeightGet();
152  }
153 
154  return hist;
155 }
156 
157 
158 
159 unsigned int
161 {
162  return _listOfSamples.size();
163 }
164 
165 
virtual tf::Vector3 ExpectedValueGet() const
XmlRpcServer s
virtual WeightedSample< tf::Vector3 > SampleGet(unsigned int particle) const
static const unsigned int NUM_CONDARG
TFSIMD_FORCE_INLINE const tfScalar & z() const
void getParticleCloud(const tf::Vector3 &step, double threshold, sensor_msgs::PointCloud &cloud) const
Get evenly distributed particle cloud.
TFSIMD_FORCE_INLINE const tfScalar & y() const
TFSIMD_FORCE_INLINE const tfScalar & x() const
virtual unsigned int numParticlesGet() const
int min(int a, int b)
static const int rgb[]
Definition: rgb.h:4
virtual ~MCPdfVector()
Destructor.
MatrixWrapper::Matrix getHistogram(const tf::Vector3 &min, const tf::Vector3 &max, const tf::Vector3 &step) const
Get pos histogram from certain area.


people_tracking_filter
Author(s): Caroline Pantofaru
autogenerated on Fri Jun 7 2019 22:07:49