voxel_layer.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, 2013, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Eitan Marder-Eppstein
36  * David V. Lu!!
37  *********************************************************************/
38 #include <costmap_2d/voxel_layer.h>
41 
42 #define VOXEL_BITS 16
44 
48 
51 
52 namespace costmap_2d
53 {
54 
56 {
58  ros::NodeHandle private_nh("~/" + name_);
59 
60  private_nh.param("publish_voxel_map", publish_voxel_, false);
61  if (publish_voxel_)
62  voxel_pub_ = private_nh.advertise < costmap_2d::VoxelGrid > ("voxel_grid", 1);
63 
64  clearing_endpoints_pub_ = private_nh.advertise<sensor_msgs::PointCloud>("clearing_endpoints", 1);
65 }
66 
68 {
69  voxel_dsrv_ = new dynamic_reconfigure::Server<costmap_2d::VoxelPluginConfig>(nh);
70  dynamic_reconfigure::Server<costmap_2d::VoxelPluginConfig>::CallbackType cb = boost::bind(
71  &VoxelLayer::reconfigureCB, this, _1, _2);
72  voxel_dsrv_->setCallback(cb);
73 }
74 
76 {
77  if (voxel_dsrv_)
78  delete voxel_dsrv_;
79 }
80 
81 void VoxelLayer::reconfigureCB(costmap_2d::VoxelPluginConfig &config, uint32_t level)
82 {
83  enabled_ = config.enabled;
84  footprint_clearing_enabled_ = config.footprint_clearing_enabled;
85  max_obstacle_height_ = config.max_obstacle_height;
86  size_z_ = config.z_voxels;
87  origin_z_ = config.origin_z;
88  z_resolution_ = config.z_resolution;
89  unknown_threshold_ = config.unknown_threshold + (VOXEL_BITS - size_z_);
90  mark_threshold_ = config.mark_threshold;
91  combination_method_ = config.combination_method;
92  matchSize();
93 }
94 
96 {
100 }
101 
103 {
104  deactivate();
105  resetMaps();
106  voxel_grid_.reset();
107  activate();
108 }
109 
111 {
113  voxel_grid_.reset();
114 }
115 
116 void VoxelLayer::updateBounds(double robot_x, double robot_y, double robot_yaw, double* min_x,
117  double* min_y, double* max_x, double* max_y)
118 {
119  if (rolling_window_)
120  updateOrigin(robot_x - getSizeInMetersX() / 2, robot_y - getSizeInMetersY() / 2);
121  if (!enabled_)
122  return;
123  useExtraBounds(min_x, min_y, max_x, max_y);
124 
125  bool current = true;
126  std::vector<Observation> observations, clearing_observations;
127 
128  // get the marking observations
129  current = getMarkingObservations(observations) && current;
130 
131  // get the clearing observations
132  current = getClearingObservations(clearing_observations) && current;
133 
134  // update the global current status
135  current_ = current;
136 
137  // raytrace freespace
138  for (unsigned int i = 0; i < clearing_observations.size(); ++i)
139  {
140  raytraceFreespace(clearing_observations[i], min_x, min_y, max_x, max_y);
141  }
142 
143  // place the new obstacles into a priority queue... each with a priority of zero to begin with
144  for (std::vector<Observation>::const_iterator it = observations.begin(); it != observations.end(); ++it)
145  {
146  const Observation& obs = *it;
147 
148  const sensor_msgs::PointCloud2& cloud = *(obs.cloud_);
149 
150  double sq_obstacle_range = obs.obstacle_range_ * obs.obstacle_range_;
151 
155 
156  for (unsigned int i = 0; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z)
157  {
158  // if the obstacle is too high or too far away from the robot we won't add it
159  if (*iter_z > max_obstacle_height_)
160  continue;
161 
162  // compute the squared distance from the hitpoint to the pointcloud's origin
163  double sq_dist = (*iter_x - obs.origin_.x) * (*iter_x - obs.origin_.x)
164  + (*iter_y - obs.origin_.y) * (*iter_y - obs.origin_.y)
165  + (*iter_z - obs.origin_.z) * (*iter_z - obs.origin_.z);
166 
167  // if the point is far enough away... we won't consider it
168  if (sq_dist >= sq_obstacle_range)
169  continue;
170 
171  // now we need to compute the map coordinates for the observation
172  unsigned int mx, my, mz;
173  if (*iter_z < origin_z_)
174  {
175  if (!worldToMap3D(*iter_x, *iter_y, origin_z_, mx, my, mz))
176  continue;
177  }
178  else if (!worldToMap3D(*iter_x, *iter_y, *iter_z, mx, my, mz))
179  {
180  continue;
181  }
182 
183  // mark the cell in the voxel grid and check if we should also mark it in the costmap
184  if (voxel_grid_.markVoxelInMap(mx, my, mz, mark_threshold_))
185  {
186  unsigned int index = getIndex(mx, my);
187 
188  costmap_[index] = LETHAL_OBSTACLE;
189  touch(double(*iter_x), double(*iter_y), min_x, min_y, max_x, max_y);
190  }
191  }
192  }
193 
194  if (publish_voxel_)
195  {
196  costmap_2d::VoxelGrid grid_msg;
197  unsigned int size = voxel_grid_.sizeX() * voxel_grid_.sizeY();
198  grid_msg.size_x = voxel_grid_.sizeX();
199  grid_msg.size_y = voxel_grid_.sizeY();
200  grid_msg.size_z = voxel_grid_.sizeZ();
201  grid_msg.data.resize(size);
202  memcpy(&grid_msg.data[0], voxel_grid_.getData(), size * sizeof(unsigned int));
203 
204  grid_msg.origin.x = origin_x_;
205  grid_msg.origin.y = origin_y_;
206  grid_msg.origin.z = origin_z_;
207 
208  grid_msg.resolutions.x = resolution_;
209  grid_msg.resolutions.y = resolution_;
210  grid_msg.resolutions.z = z_resolution_;
211  grid_msg.header.frame_id = global_frame_;
212  grid_msg.header.stamp = ros::Time::now();
213  voxel_pub_.publish(grid_msg);
214  }
215 
216  updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
217 }
218 
219 void VoxelLayer::clearNonLethal(double wx, double wy, double w_size_x, double w_size_y, bool clear_no_info)
220 {
221  // get the cell coordinates of the center point of the window
222  unsigned int mx, my;
223  if (!worldToMap(wx, wy, mx, my))
224  return;
225 
226  // compute the bounds of the window
227  double start_x = wx - w_size_x / 2;
228  double start_y = wy - w_size_y / 2;
229  double end_x = start_x + w_size_x;
230  double end_y = start_y + w_size_y;
231 
232  // scale the window based on the bounds of the costmap
233  start_x = std::max(origin_x_, start_x);
234  start_y = std::max(origin_y_, start_y);
235 
236  end_x = std::min(origin_x_ + getSizeInMetersX(), end_x);
237  end_y = std::min(origin_y_ + getSizeInMetersY(), end_y);
238 
239  // get the map coordinates of the bounds of the window
240  unsigned int map_sx, map_sy, map_ex, map_ey;
241 
242  // check for legality just in case
243  if (!worldToMap(start_x, start_y, map_sx, map_sy) || !worldToMap(end_x, end_y, map_ex, map_ey))
244  return;
245 
246  // we know that we want to clear all non-lethal obstacles in this window to get it ready for inflation
247  unsigned int index = getIndex(map_sx, map_sy);
248  unsigned char* current = &costmap_[index];
249  for (unsigned int j = map_sy; j <= map_ey; ++j)
250  {
251  for (unsigned int i = map_sx; i <= map_ex; ++i)
252  {
253  // if the cell is a lethal obstacle... we'll keep it and queue it, otherwise... we'll clear it
254  if (*current != LETHAL_OBSTACLE)
255  {
256  if (clear_no_info || *current != NO_INFORMATION)
257  {
258  *current = FREE_SPACE;
260  }
261  }
262  current++;
263  index++;
264  }
265  current += size_x_ - (map_ex - map_sx) - 1;
266  index += size_x_ - (map_ex - map_sx) - 1;
267  }
268 }
269 
270 void VoxelLayer::raytraceFreespace(const Observation& clearing_observation, double* min_x, double* min_y,
271  double* max_x, double* max_y)
272 {
273  size_t clearing_observation_cloud_size = clearing_observation.cloud_->height * clearing_observation.cloud_->width;
274  if (clearing_observation_cloud_size == 0)
275  return;
276 
277  double sensor_x, sensor_y, sensor_z;
278  double ox = clearing_observation.origin_.x;
279  double oy = clearing_observation.origin_.y;
280  double oz = clearing_observation.origin_.z;
281 
282  if (!worldToMap3DFloat(ox, oy, oz, sensor_x, sensor_y, sensor_z))
283  {
285  1.0,
286  "The origin for the sensor at (%.2f, %.2f, %.2f) is out of map bounds. So, the costmap cannot raytrace for it.",
287  ox, oy, oz);
288  return;
289  }
290 
291  bool publish_clearing_points = (clearing_endpoints_pub_.getNumSubscribers() > 0);
292  if (publish_clearing_points)
293  {
294  clearing_endpoints_.points.clear();
295  clearing_endpoints_.points.reserve(clearing_observation_cloud_size);
296  }
297 
298  // we can pre-compute the enpoints of the map outside of the inner loop... we'll need these later
299  double map_end_x = origin_x_ + getSizeInMetersX();
300  double map_end_y = origin_y_ + getSizeInMetersY();
301 
302  sensor_msgs::PointCloud2ConstIterator<float> iter_x(*(clearing_observation.cloud_), "x");
303  sensor_msgs::PointCloud2ConstIterator<float> iter_y(*(clearing_observation.cloud_), "y");
304  sensor_msgs::PointCloud2ConstIterator<float> iter_z(*(clearing_observation.cloud_), "z");
305 
306  for (;iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z)
307  {
308  double wpx = *iter_x;
309  double wpy = *iter_y;
310  double wpz = *iter_z;
311 
312  double distance = dist(ox, oy, oz, wpx, wpy, wpz);
313  double scaling_fact = 1.0;
314  scaling_fact = std::max(std::min(scaling_fact, (distance - 2 * resolution_) / distance), 0.0);
315  wpx = scaling_fact * (wpx - ox) + ox;
316  wpy = scaling_fact * (wpy - oy) + oy;
317  wpz = scaling_fact * (wpz - oz) + oz;
318 
319  double a = wpx - ox;
320  double b = wpy - oy;
321  double c = wpz - oz;
322  double t = 1.0;
323 
324  // we can only raytrace to a maximum z height
325  if (wpz > max_obstacle_height_)
326  {
327  // we know we want the vector's z value to be max_z
328  t = std::max(0.0, std::min(t, (max_obstacle_height_ - 0.01 - oz) / c));
329  }
330  // and we can only raytrace down to the floor
331  else if (wpz < origin_z_)
332  {
333  // we know we want the vector's z value to be 0.0
334  t = std::min(t, (origin_z_ - oz) / c);
335  }
336 
337  // the minimum value to raytrace from is the origin
338  if (wpx < origin_x_)
339  {
340  t = std::min(t, (origin_x_ - ox) / a);
341  }
342  if (wpy < origin_y_)
343  {
344  t = std::min(t, (origin_y_ - oy) / b);
345  }
346 
347  // the maximum value to raytrace to is the end of the map
348  if (wpx > map_end_x)
349  {
350  t = std::min(t, (map_end_x - ox) / a);
351  }
352  if (wpy > map_end_y)
353  {
354  t = std::min(t, (map_end_y - oy) / b);
355  }
356 
357  wpx = ox + a * t;
358  wpy = oy + b * t;
359  wpz = oz + c * t;
360 
361  double point_x, point_y, point_z;
362  if (worldToMap3DFloat(wpx, wpy, wpz, point_x, point_y, point_z))
363  {
364  unsigned int cell_raytrace_range = cellDistance(clearing_observation.raytrace_range_);
365 
366  // voxel_grid_.markVoxelLine(sensor_x, sensor_y, sensor_z, point_x, point_y, point_z);
367  voxel_grid_.clearVoxelLineInMap(sensor_x, sensor_y, sensor_z, point_x, point_y, point_z, costmap_,
369  cell_raytrace_range);
370 
371  updateRaytraceBounds(ox, oy, wpx, wpy, clearing_observation.raytrace_range_, min_x, min_y, max_x, max_y);
372 
373  if (publish_clearing_points)
374  {
375  geometry_msgs::Point32 point;
376  point.x = wpx;
377  point.y = wpy;
378  point.z = wpz;
379  clearing_endpoints_.points.push_back(point);
380  }
381  }
382  }
383 
384  if (publish_clearing_points)
385  {
386  clearing_endpoints_.header.frame_id = global_frame_;
387  clearing_endpoints_.header.stamp = clearing_observation.cloud_->header.stamp;
388  clearing_endpoints_.header.seq = clearing_observation.cloud_->header.seq;
389 
391  }
392 }
393 
394 void VoxelLayer::updateOrigin(double new_origin_x, double new_origin_y)
395 {
396  // project the new origin into the grid
397  int cell_ox, cell_oy;
398  cell_ox = int((new_origin_x - origin_x_) / resolution_);
399  cell_oy = int((new_origin_y - origin_y_) / resolution_);
400 
401  // compute the associated world coordinates for the origin cell
402  // beacuase we want to keep things grid-aligned
403  double new_grid_ox, new_grid_oy;
404  new_grid_ox = origin_x_ + cell_ox * resolution_;
405  new_grid_oy = origin_y_ + cell_oy * resolution_;
406 
407  // To save casting from unsigned int to int a bunch of times
408  int size_x = size_x_;
409  int size_y = size_y_;
410 
411  // we need to compute the overlap of the new and existing windows
412  int lower_left_x, lower_left_y, upper_right_x, upper_right_y;
413  lower_left_x = std::min(std::max(cell_ox, 0), size_x);
414  lower_left_y = std::min(std::max(cell_oy, 0), size_y);
415  upper_right_x = std::min(std::max(cell_ox + size_x, 0), size_x);
416  upper_right_y = std::min(std::max(cell_oy + size_y, 0), size_y);
417 
418  unsigned int cell_size_x = upper_right_x - lower_left_x;
419  unsigned int cell_size_y = upper_right_y - lower_left_y;
420 
421  // we need a map to store the obstacles in the window temporarily
422  unsigned char* local_map = new unsigned char[cell_size_x * cell_size_y];
423  unsigned int* local_voxel_map = new unsigned int[cell_size_x * cell_size_y];
424  unsigned int* voxel_map = voxel_grid_.getData();
425 
426  // copy the local window in the costmap to the local map
427  copyMapRegion(costmap_, lower_left_x, lower_left_y, size_x_, local_map, 0, 0, cell_size_x, cell_size_x, cell_size_y);
428  copyMapRegion(voxel_map, lower_left_x, lower_left_y, size_x_, local_voxel_map, 0, 0, cell_size_x, cell_size_x,
429  cell_size_y);
430 
431  // we'll reset our maps to unknown space if appropriate
432  resetMaps();
433 
434  // update the origin with the appropriate world coordinates
435  origin_x_ = new_grid_ox;
436  origin_y_ = new_grid_oy;
437 
438  // compute the starting cell location for copying data back in
439  int start_x = lower_left_x - cell_ox;
440  int start_y = lower_left_y - cell_oy;
441 
442  // now we want to copy the overlapping information back into the map, but in its new location
443  copyMapRegion(local_map, 0, 0, cell_size_x, costmap_, start_x, start_y, size_x_, cell_size_x, cell_size_y);
444  copyMapRegion(local_voxel_map, 0, 0, cell_size_x, voxel_map, start_x, start_y, size_x_, cell_size_x, cell_size_y);
445 
446  // make sure to clean up
447  delete[] local_map;
448  delete[] local_voxel_map;
449 }
450 
451 } // namespace costmap_2d
double getSizeInMetersX() const
Accessor for the x size of the costmap in meters.
Definition: costmap_2d.cpp:440
geometry_msgs::Point origin_
Definition: observation.h:96
unsigned int unknown_threshold_
Definition: voxel_layer.h:102
bool getMarkingObservations(std::vector< costmap_2d::Observation > &marking_observations) const
Get the observations used to mark space.
sensor_msgs::PointCloud clearing_endpoints_
Definition: voxel_layer.h:104
virtual void resetMaps()
Resets the costmap and static_map to be unknown space.
void clearNonLethal(double wx, double wy, double w_size_x, double w_size_y, bool clear_no_info)
ros::Publisher voxel_pub_
Definition: voxel_layer.h:99
unsigned int cellDistance(double world_dist)
Given distance in the world... convert it to cells.
Definition: costmap_2d.cpp:181
unsigned int size_y_
Definition: costmap_2d.h:422
virtual void deactivate()
Stop publishers.
ros::Publisher clearing_endpoints_pub_
Definition: voxel_layer.h:103
unsigned int mark_threshold_
Definition: voxel_layer.h:102
void updateRaytraceBounds(double ox, double oy, double wx, double wy, double range, double *min_x, double *min_y, double *max_x, double *max_y)
bool markVoxelInMap(unsigned int x, unsigned int y, unsigned int z, unsigned int marked_threshold)
unsigned int getIndex(unsigned int mx, unsigned int my) const
Given two map coordinates... compute the associated index.
Definition: costmap_2d.h:171
voxel_grid::VoxelGrid voxel_grid_
Definition: voxel_layer.h:100
Stores an observation in terms of a point cloud and the origin of the source.
Definition: observation.h:46
virtual void matchSize()
Implement this to make this layer match the size of the parent costmap.
Definition: voxel_layer.cpp:95
unsigned int size_x_
Definition: costmap_2d.h:421
static const unsigned char FREE_SPACE
Definition: cost_values.h:45
double getSizeInMetersY() const
Accessor for the y size of the costmap in meters.
Definition: costmap_2d.cpp:445
geometry_msgs::TransformStamped t
void useExtraBounds(double *min_x, double *min_y, double *max_x, double *max_y)
void clearVoxelLineInMap(double x0, double y0, double z0, double x1, double y1, double z1, unsigned char *map_2d, unsigned int unknown_threshold, unsigned int mark_threshold, unsigned char free_cost=0, unsigned char unknown_cost=255, unsigned int max_length=UINT_MAX)
std::string name_
Definition: layer.h:124
void copyMapRegion(data_type *source_map, unsigned int sm_lower_left_x, unsigned int sm_lower_left_y, unsigned int sm_size_x, data_type *dest_map, unsigned int dm_lower_left_x, unsigned int dm_lower_left_y, unsigned int dm_size_x, unsigned int region_size_x, unsigned int region_size_y)
Copy a region of a source map into a destination map.
Definition: costmap_2d.h:315
double dist(double x0, double y0, double z0, double x1, double y1, double z1)
Definition: voxel_layer.h:142
double max_obstacle_height_
Max Obstacle Height.
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void resize(unsigned int size_x, unsigned int size_y, unsigned int size_z)
void publish(const boost::shared_ptr< M > &message) const
double distance(double x0, double y0, double x1, double y1)
Definition: costmap_math.h:58
virtual void activate()
Restart publishers if they&#39;ve been stopped.
unsigned int sizeY()
virtual void reset()
Takes in point clouds from sensors, transforms them to the desired frame, and stores them...
void updateOrigin(double new_origin_x, double new_origin_y)
Move the origin of the costmap to a new location.... keeping data when it can.
virtual void setupDynamicReconfigure(ros::NodeHandle &nh)
Definition: voxel_layer.cpp:67
virtual void onInitialize()
This is called at the end of initialize(). Override to implement subclass-specific initialization...
Definition: voxel_layer.cpp:55
#define ROS_WARN_THROTTLE(period,...)
virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
This is called by the LayeredCostmap to poll this plugin as to how much of the costmap it needs to up...
bool worldToMap3D(double wx, double wy, double wz, unsigned int &mx, unsigned int &my, unsigned int &mz)
Definition: voxel_layer.h:119
virtual void resetMaps()
Resets the costmap and static_map to be unknown space.
Definition: costmap_2d.cpp:87
unsigned int sizeX()
dynamic_reconfigure::Server< costmap_2d::VoxelPluginConfig > * voxel_dsrv_
Definition: voxel_layer.h:96
virtual void raytraceFreespace(const costmap_2d::Observation &clearing_observation, double *min_x, double *min_y, double *max_x, double *max_y)
Clear freespace based on one observation.
unsigned int size_z_
Definition: voxel_layer.h:102
virtual void matchSize()
Implement this to make this layer match the size of the parent costmap.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void updateFootprint(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
bool enabled_
Currently this var is managed by subclasses. TODO: make this managed by this class and/or container c...
Definition: layer.h:123
uint32_t * getData()
virtual void onInitialize()
This is called at the end of initialize(). Override to implement subclass-specific initialization...
sensor_msgs::PointCloud2 * cloud_
Definition: observation.h:97
static const unsigned char LETHAL_OBSTACLE
Definition: cost_values.h:43
static const unsigned char NO_INFORMATION
Definition: cost_values.h:42
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.
Definition: costmap_2d.cpp:208
void clearVoxelColumn(unsigned int index)
static Time now()
void touch(double x, double y, double *min_x, double *min_y, double *max_x, double *max_y)
#define ROS_ASSERT(cond)
bool worldToMap3DFloat(double wx, double wy, double wz, double &mx, double &my, double &mz)
Definition: voxel_layer.h:106
uint32_t getNumSubscribers() const
unsigned char * costmap_
Definition: costmap_2d.h:426
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
unsigned int sizeZ()
bool getClearingObservations(std::vector< costmap_2d::Observation > &clearing_observations) const
Get the observations used to clear space.
std::string global_frame_
The global frame for the costmap.
void reconfigureCB(costmap_2d::VoxelPluginConfig &config, uint32_t level)
Definition: voxel_layer.cpp:81
#define VOXEL_BITS
Definition: voxel_layer.cpp:42


costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Wed Jun 22 2022 02:07:03