utest.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018, Locus Robotics
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 copyright holder 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 HOLDER 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 #include <gtest/gtest.h>
36 #include <algorithm>
37 #include <vector>
38 
39 using nav_grid::Index;
40 
41 template<class iterator_type>
42 int countIterations(iterator_type it, int max_iterations = 1000)
43 {
44  int count = 0;
45  iterator_type end = it.end();
46  for ( ; it != end; ++it)
47  {
48  ++count;
49  if (count >= max_iterations) break;
50  }
51  return count;
52 }
53 
54 TEST(WholeGrid, whole_grid)
55 {
57  info.width = 5;
58  info.height = 8;
59  int count = 0;
60  for (nav_grid_iterators::WholeGrid it(info); it != it.end(); ++it)
61  {
62  Index i = *it;
63  ASSERT_EQ(i.x, count % info.width);
64  ASSERT_EQ(i.y, count / info.width);
65  ++count;
66  }
67  ASSERT_EQ(count, 40);
68 }
69 
70 TEST(WholeGrid, whole_grid_range)
71 {
73  info.width = 3;
74  info.height = 6;
75  int count = 0;
76  for (Index i : nav_grid_iterators::WholeGrid(info))
77  {
78  ASSERT_EQ(i.x, count % info.width);
79  ASSERT_EQ(i.y, count / info.width);
80  ++count;
81  }
82  ASSERT_EQ(count, 18);
83 }
84 
85 TEST(WholeGrid, std_stuff)
86 {
88  info.width = 8;
89  info.height = 2;
91 
92  std::vector<Index> vec;
93  std::copy(wg.begin(), wg.end(), std::back_inserter(vec));
94  for (int count = 0; count < 16; ++count)
95  {
96  Index& i = vec[count];
97  ASSERT_EQ(i.x, count % info.width);
98  ASSERT_EQ(i.y, count / info.width);
99  }
100 }
101 
102 TEST(SubGrid, sub_grid)
103 {
105  info.width = 5;
106  info.height = 8;
107  int count = 0;
108  for (Index i : nav_grid_iterators::SubGrid(&info, 1, 2, 2, 3))
109  {
110  ASSERT_EQ(i.x, static_cast<unsigned int>(1 + count % 2));
111  ASSERT_EQ(i.y, static_cast<unsigned int>(2 + count / 2));
112  ++count;
113  }
114  ASSERT_EQ(count, 6);
115 
116  ASSERT_EQ(countIterations(nav_grid_iterators::SubGrid(&info, 1, 3, 4, 1)), 4);
117  ASSERT_EQ(countIterations(nav_grid_iterators::SubGrid(&info, 1, 3, 2, 2)), 4);
118  nav_core2::UIntBounds bounds(1, 3, 4, 3);
119  ASSERT_EQ(countIterations(nav_grid_iterators::SubGrid(&info, bounds)), 4);
120 
121  // Empty Bounds
122  bounds.reset();
123  ASSERT_EQ(countIterations(nav_grid_iterators::SubGrid(&info, bounds)), 0);
124 
125  // Partially Overlapping Bounds
126  bounds.touch(3, 2);
127  bounds.touch(6, 3);
128  ASSERT_EQ(countIterations(nav_grid_iterators::SubGrid(&info, bounds)), 4);
129 
130  bounds.reset();
131  bounds.touch(1, 6);
132  bounds.touch(3, 9);
133  ASSERT_EQ(countIterations(nav_grid_iterators::SubGrid(&info, bounds)), 6);
134 
135  // Different empty bounds
136  nav_core2::UIntBounds empty(1, 0, 0, 0);
137  ASSERT_EQ(countIterations(nav_grid_iterators::SubGrid(&info, empty)), 0);
138 }
139 
140 TEST(SubGrid, equality)
141 {
143  info.width = 5;
144  info.height = 8;
145  nav_grid_iterators::SubGrid it1(&info, 1, 2, 2, 3);
146  nav_grid_iterators::SubGrid it2(&info, 1, 2, 1, 1);
147  ASSERT_FALSE(it1 == it2);
148 }
149 
150 TEST(CircleFill, circle)
151 {
153  info.width = 8;
154  info.height = 8;
155  info.resolution = 1.0;
156 
157  ASSERT_EQ(countIterations(nav_grid_iterators::CircleFill(&info, 4.0, 4.0, 3.0)), 32);
158  ASSERT_EQ(countIterations(nav_grid_iterators::CircleFill(&info, 4.3, 4.0, 3.0)), 28);
159  ASSERT_EQ(countIterations(nav_grid_iterators::CircleFill(&info, 4.0, 4.0, 8.0)), 64);
160  ASSERT_EQ(countIterations(nav_grid_iterators::CircleFill(&info, 14.0, 4.0, 1.0)), 0);
161  ASSERT_EQ(countIterations(nav_grid_iterators::CircleFill(&info, 0.0, 4.0, 4.0)), 26);
162  ASSERT_EQ(countIterations(nav_grid_iterators::CircleFill(&info, 4.0, 4.0, 3.0).begin()), 32);
163 }
164 
165 TEST(CircleFill, equality)
166 {
168  info.width = 5;
169  info.height = 8;
170  nav_grid_iterators::CircleFill it1(&info, 4.0, 4.0, 8.0);
171  nav_grid_iterators::CircleFill it2(&info, 1.0, 1.0, 100.0);
172  ASSERT_FALSE(it1 == it2);
173 }
174 
175 TEST(CircleOutline, circle_outline)
176 {
178  info.width = 8;
179  info.height = 8;
180  info.resolution = 1.0;
181 
182  unsigned int size = 0;
183  EXPECT_EQ(countIterations(nav_grid_iterators::CircleOutline(&info, 4.0, 4.0, size++)), 1);
184  EXPECT_EQ(countIterations(nav_grid_iterators::CircleOutline(&info, 4.0, 4.0, size++)), 8);
185  EXPECT_EQ(countIterations(nav_grid_iterators::CircleOutline(&info, 4.0, 4.0, size++)), 16);
186  EXPECT_EQ(countIterations(nav_grid_iterators::CircleOutline(&info, 4.0, 4.0, size++)), 20);
187  EXPECT_EQ(countIterations(nav_grid_iterators::CircleOutline(&info, 4.0, 4.0, size++)), 14);
188  EXPECT_EQ(countIterations(nav_grid_iterators::CircleOutline(&info, 4.0, 4.0, size++)), 5);
189  EXPECT_EQ(countIterations(nav_grid_iterators::CircleOutline(&info, 4.0, 4.0, size++)), 0);
190  EXPECT_EQ(countIterations(nav_grid_iterators::CircleOutline(&info, 4.0, 4.0, size++)), 0);
191 }
192 
193 TEST(CircleOutline, equality)
194 {
196  info.width = 5;
197  info.height = 8;
198  nav_grid_iterators::CircleOutline it1(&info, 3.0, 1.0, 1.0);
199  nav_grid_iterators::CircleOutline it2(&info, 1.0, 1.0, 3.0);
200  ASSERT_FALSE(it1 == it2);
201 }
202 
203 TEST(Spiral, spiral)
204 {
206  info.width = 8;
207  info.height = 8;
208  info.resolution = 1.0;
209  info.origin_x = 0.0;
210  info.origin_y = 0.0;
211  ASSERT_EQ(countIterations(nav_grid_iterators::Spiral(&info, 4.0, 4.0, 3.0)), 32);
212  ASSERT_EQ(countIterations(nav_grid_iterators::Spiral(&info, 4.3, 4.0, 3.0)), 28);
213  ASSERT_EQ(countIterations(nav_grid_iterators::Spiral(&info, 4.0, 4.0, 8.0)), 64);
214  ASSERT_EQ(countIterations(nav_grid_iterators::Spiral(&info, 14.0, 4.0, 1.0)), 0);
215  ASSERT_EQ(countIterations(nav_grid_iterators::Spiral(&info, 0.0, 4.0, 4.0)), 26);
216 }
217 
218 TEST(Spiral, equality)
219 {
221  info.width = 5;
222  info.height = 8;
223  nav_grid_iterators::Spiral it1(&info, 1.0, 1.0, 1.0);
224  nav_grid_iterators::Spiral it2(&info, 1.0, 1.0, 3.0);
225  ASSERT_FALSE(it1 == it2);
226 }
227 
228 TEST(Line, signed_line)
229 {
231  info.width = 10;
232  info.height = 10;
233  info.resolution = 1.0;
234  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, 0, 0, 0)), 1);
235  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, 0, 3, 0)), 4);
236  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, 0, -3, 0)), 1);
237  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 3, 0, 0, 0)), 4);
238  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, -3, 0, 0, 0)), 1);
239  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, -3, 0, 0, 0, false)), 0);
240  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, 0, 0, 3)), 4);
241  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, 0, 0, -3)), 1);
242  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, 3, 0, 0)), 4);
243  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, -3, 0, 0)), 1);
244  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, 0, 1, 9)), 10);
245  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 1, 9, 0, 0)), 10);
246  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 9, 1, 0, 0)), 10);
247  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, 0, 9, 1)), 10);
248 
249  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, -5, 5, 15, 5)), 10);
250  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 15, 5, -5, 5)), 10);
251  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 15, 5, 15, 7)), 0);
252 
253  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, -1, -5, -1, -7)), 0);
254 }
255 
256 TEST(Line, signed_line_diff_res)
257 {
258  // This is the same test as above with a reduced resolution. Most of the coordinates are divided by 10
259  // (with an additional 0.05 in some places to avoid floating point errors)
261  info.width = 10;
262  info.height = 10;
263  info.resolution = 0.1;
264  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, 0, 0, 0)), 1);
265  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, 0, 0.35, 0)), 4);
266  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, 0, -0.35, 0)), 1);
267  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0.35, 0, 0, 0)), 4);
268  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, -0.35, 0, 0, 0)), 1);
269  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, -0.35, 0, 0, 0, false)), 0);
270  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, 0, 0, 0.35)), 4);
271  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, 0, 0, -0.35)), 1);
272  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, 0.35, 0, 0)), 4);
273  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, -0.35, 0, 0)), 1);
274  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, 0, 0.15, 0.95)), 10);
275  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0.15, 0.95, 0, 0)), 10);
276  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0.95, 0.15, 0, 0)), 10);
277  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 0, 0, 0.95, 0.15)), 10);
278 
279  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, -0.5, 0.5, 1.5, 0.5)), 10);
280  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 1.5, 0.5, -0.55, 0.55)), 10);
281  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 1.5, 0.5, 1.5, 0.75)), 0);
282 
283  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, -0.1, -0.5, -0.1, -0.7)), 0);
284 }
285 
286 TEST(Line, random_test_case)
287 {
289  info.width = 795;
290  info.height = 925;
291  info.resolution = 0.05;
292  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 6.2402, 30.651832, 2.805347, 22.8941, false, false)), 224);
293  EXPECT_EQ(countIterations(nav_grid_iterators::Line(&info, 6.2402, 30.651832, 2.805347, 22.8941, true, false)), 225);
294 }
295 
296 TEST(Line, equality)
297 {
299  info.width = 5;
300  info.height = 8;
301  nav_grid_iterators::Line it1(&info, 0, 0, 5, 5);
302  nav_grid_iterators::Line it2(&info, 0, 0, 1, 1);
303  ASSERT_FALSE(it1 == it2);
304 }
305 
306 nav_2d_msgs::Point2D make_point(double x, double y)
307 {
308  nav_2d_msgs::Point2D pt;
309  pt.x = x;
310  pt.y = y;
311  return pt;
312 }
313 
314 TEST(Polygon, polygon)
315 {
317  // First check to make sure it works when the polygon is completely on the grid
318  info.width = 10;
319  info.height = 10;
320  info.resolution = 1.0;
321  nav_2d_msgs::Polygon2D simple_square;
322  simple_square.points.push_back(make_point(1.4, 1.4));
323  simple_square.points.push_back(make_point(1.4, 3.6));
324  simple_square.points.push_back(make_point(3.6, 3.6));
325  simple_square.points.push_back(make_point(3.6, 1.4));
326 
327  EXPECT_EQ(countIterations(nav_grid_iterators::PolygonOutline(&info, simple_square)), 8);
328  EXPECT_EQ(countIterations(nav_grid_iterators::PolygonFill(&info, simple_square)), 9);
329 
330  // Then do it again when it is only partially on the grid
331  info.height = 3;
332  EXPECT_EQ(countIterations(nav_grid_iterators::PolygonOutline(&info, simple_square)), 5);
333  EXPECT_EQ(countIterations(nav_grid_iterators::PolygonFill(&info, simple_square)), 6);
334 
335  // Then check when it is completely off the grid
336  info.resolution = 0.1;
337  EXPECT_EQ(countIterations(nav_grid_iterators::PolygonOutline(&info, simple_square)), 0);
338  EXPECT_EQ(countIterations(nav_grid_iterators::PolygonFill(&info, simple_square)), 0);
339 }
340 
341 TEST(Polygon, empty_polygon)
342 {
344  info.width = 10;
345  info.height = 10;
346  info.resolution = 1.0;
347  nav_2d_msgs::Polygon2D empty_polygon;
348 
349  EXPECT_EQ(countIterations(nav_grid_iterators::PolygonOutline(&info, empty_polygon)), 0);
350  EXPECT_EQ(countIterations(nav_grid_iterators::PolygonFill(&info, empty_polygon)), 0);
351 }
352 
353 TEST(Polygon, equality)
354 {
356  info.width = 10;
357  info.height = 10;
358  info.resolution = 1.0;
359  nav_2d_msgs::Polygon2D simple_square;
360  simple_square.points.push_back(make_point(1.4, 1.4));
361  simple_square.points.push_back(make_point(1.4, 3.6));
362  simple_square.points.push_back(make_point(3.6, 3.6));
363  simple_square.points.push_back(make_point(3.6, 1.4));
364 
365  nav_2d_msgs::Polygon2D triangle;
366  triangle.points.push_back(make_point(1.4, 1.4));
367  triangle.points.push_back(make_point(1.4, 3.6));
368  triangle.points.push_back(make_point(3.6, 3.6));
369 
370 
371  nav_grid_iterators::PolygonOutline it1(&info, simple_square);
372  nav_grid_iterators::PolygonOutline it2(&info, triangle);
373  ASSERT_FALSE(it1 == it2);
374 
375  nav_grid_iterators::PolygonFill it3(&info, simple_square);
376  nav_grid_iterators::PolygonFill it4(&info, triangle);
377  ASSERT_FALSE(it3 == it4);
378 }
379 
380 TEST(Iterators, test_copy)
381 {
382  // This test will fail to compile if you cannot use the copy operator
384  info.width = 10;
385  info.height = 10;
386  info.resolution = 1.0;
387 
388  nav_2d_msgs::Polygon2D simple_square;
389  simple_square.points.push_back(make_point(1.4, 1.4));
390  simple_square.points.push_back(make_point(1.4, 3.6));
391  simple_square.points.push_back(make_point(3.6, 3.6));
392  simple_square.points.push_back(make_point(3.6, 1.4));
393 
394  nav_grid_iterators::WholeGrid whole_grid(info);
395  whole_grid = whole_grid.begin();
396  nav_grid_iterators::SubGrid sub_grid(&info, 1, 2, 2, 3);
397  sub_grid = sub_grid.begin();
398  nav_grid_iterators::CircleFill cf(&info, 4.0, 4.0, 3.0);
399  cf = cf.begin();
400  nav_grid_iterators::CircleOutline co(&info, 4.0, 4.0, 3.0);
401  co = co.begin();
402  nav_grid_iterators::Spiral spiral(&info, 4.0, 4.0, 3.0);
403  spiral = spiral.begin();
404  nav_grid_iterators::Line line(&info, 0, 0, 0, 0);
405  line = line.begin();
406  nav_grid_iterators::PolygonOutline po(&info, simple_square);
407  po = po.begin();
408  nav_grid_iterators::PolygonFill pf(&info, simple_square);
409  pf = pf.begin();
410 }
411 
412 TEST(Iterators, test_assignment)
413 {
415  info.width = 10;
416  info.height = 10;
417  info.resolution = 1.0;
418  nav_grid_iterators::CircleFill iter1(&info, 3.0, 3.0, 1.0);
419  // Sequence should be (2, 2) (3, 2) (2, 3) (3, 3)
420  EXPECT_EQ((*iter1).x, 2U);
421  EXPECT_EQ((*iter1).y, 2U);
422 
423  nav_grid_iterators::CircleFill iter2 = iter1;
424 
425  // Effective Copy
426  EXPECT_EQ((*iter1).x, 2U);
427  EXPECT_EQ((*iter1).y, 2U);
428  EXPECT_EQ((*iter2).x, 2U);
429  EXPECT_EQ((*iter2).y, 2U);
430 
431  // Increment only iter2
432  ++iter2;
433  EXPECT_EQ((*iter1).x, 2U);
434  EXPECT_EQ((*iter1).y, 2U);
435  EXPECT_EQ((*iter2).x, 3U);
436  EXPECT_EQ((*iter2).y, 2U);
437 
438  // Increment first to match
439  ++iter1;
440  EXPECT_EQ((*iter1).x, 3U);
441  EXPECT_EQ((*iter1).y, 2U);
442  EXPECT_EQ((*iter2).x, 3U);
443  EXPECT_EQ((*iter2).y, 2U);
444 
445  // Increment only iter2
446  ++iter2;
447  EXPECT_EQ((*iter1).x, 3U);
448  EXPECT_EQ((*iter1).y, 2U);
449  EXPECT_EQ((*iter2).x, 2U);
450  EXPECT_EQ((*iter2).y, 3U);
451 
452  // Check copy when not at the start
453  nav_grid_iterators::CircleFill iter3 = iter1;
454  EXPECT_EQ((*iter1).x, 3U);
455  EXPECT_EQ((*iter1).y, 2U);
456  EXPECT_EQ((*iter2).x, 2U);
457  EXPECT_EQ((*iter2).y, 3U);
458  EXPECT_EQ((*iter3).x, 3U);
459  EXPECT_EQ((*iter3).y, 2U);
460 }
461 
462 int main(int argc, char **argv)
463 {
464  testing::InitGoogleTest(&argc, argv);
465  return RUN_ALL_TESTS();
466 }
Line begin() const override
Helper function for range-style iteration Equivalent to the above constructor.
Definition: line.cpp:136
int countIterations(iterator_type it, int max_iterations=1000)
Definition: utest.cpp:42
WholeGrid begin() const override
Helper function for range-style iteration Equivalent to the above constructor.
Definition: whole_grid.cpp:40
Iterates over all of the valid indexes on the outline of a polygon.
Iterates over all of the valid indexes that lie within a circle from the center out.
Definition: spiral.h:48
Iterates over all of the valid indexes that lie within a circle in row major order.
Definition: circle_fill.h:48
SubGrid begin() const override
Helper function for range-style iteration Equivalent to the above constructor.
Definition: sub_grid.cpp:68
GenericIndex< unsigned int > Index
void touch(unsigned intx, unsigned inty)
int main(int argc, char **argv)
Definition: utest.cpp:462
nav_2d_msgs::Point2D make_point(double x, double y)
Definition: utest.cpp:306
Iterates over the valid indexes that lie on the outline of a circle.
WholeGrid end() const override
Helper function for range-style iteration.
Definition: whole_grid.cpp:45
CircleOutline begin() const override
Helper function for range-style iteration Equivalent to the above constructor.
Iterates over all of the valid indexes of a line.
Definition: line.h:48
Iterates over all of the valid indexes that lie within an arbitrary polygon in row major order...
Definition: polygon_fill.h:49
TEST(WholeGrid, whole_grid)
Definition: utest.cpp:54
PolygonFill begin() const override
Helper function for range-style iteration Equivalent to the above constructor.
Iterator for looping through every index within an aligned rectangular portion of the grid...
Definition: sub_grid.h:47
CircleFill begin() const override
Helper function for range-style iteration Equivalent to the above constructor.
Spiral begin() const override
Helper function for range-style iteration Equivalent to the above constructor.
Definition: spiral.cpp:89
PolygonOutline begin() const override
Helper function for range-style iteration Equivalent to the above constructor.


nav_grid_iterators
Author(s):
autogenerated on Sun Jan 10 2021 04:08:42