trajectory_planner.h
Go to the documentation of this file.
1 /*********************************************************************
2 *
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2008, 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 the Willow Garage 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 *********************************************************************/
37 #ifndef TRAJECTORY_ROLLOUT_TRAJECTORY_PLANNER_H_
38 #define TRAJECTORY_ROLLOUT_TRAJECTORY_PLANNER_H_
39 
40 #include <vector>
41 #include <cmath>
42 
43 //for obstacle data access
44 #include <costmap_2d/costmap_2d.h>
45 #include <costmap_2d/cost_values.h>
47 
50 #include <base_local_planner/Position2DInt.h>
51 #include <base_local_planner/BaseLocalPlannerConfig.h>
52 
53 //we'll take in a path as a vector of poses
54 #include <geometry_msgs/PoseStamped.h>
55 #include <geometry_msgs/Point.h>
56 
57 //for creating a local cost grid
60 
61 namespace base_local_planner {
66  class TrajectoryPlanner{
67  friend class TrajectoryPlannerTest; //Need this for gtest to work
68  public:
105  TrajectoryPlanner(WorldModel& world_model,
106  const costmap_2d::Costmap2D& costmap,
107  std::vector<geometry_msgs::Point> footprint_spec,
108  double acc_lim_x = 1.0, double acc_lim_y = 1.0, double acc_lim_theta = 1.0,
109  double sim_time = 1.0, double sim_granularity = 0.025,
110  int vx_samples = 20, int vtheta_samples = 20,
111  double path_distance_bias = 0.6, double goal_distance_bias = 0.8, double occdist_scale = 0.2,
112  double heading_lookahead = 0.325, double oscillation_reset_dist = 0.05,
113  double escape_reset_dist = 0.10, double escape_reset_theta = M_PI_2,
114  bool holonomic_robot = true,
115  double max_vel_x = 0.5, double min_vel_x = 0.1,
116  double max_vel_th = 1.0, double min_vel_th = -1.0, double min_in_place_vel_th = 0.4,
117  double backup_vel = -0.1,
118  bool dwa = false, bool heading_scoring = false, double heading_scoring_timestep = 0.1,
119  bool meter_scoring = true,
120  bool simple_attractor = false,
121  std::vector<double> y_vels = std::vector<double>(0),
122  double stop_time_buffer = 0.2,
123  double sim_period = 0.1, double angular_sim_granularity = 0.025);
124 
129 
133  void reconfigure(BaseLocalPlannerConfig &cfg);
134 
142  Trajectory findBestPath(const geometry_msgs::PoseStamped& global_pose,
143  geometry_msgs::PoseStamped& global_vel, geometry_msgs::PoseStamped& drive_velocities);
144 
150  void updatePlan(const std::vector<geometry_msgs::PoseStamped>& new_plan, bool compute_dists = false);
151 
157  void getLocalGoal(double& x, double& y);
158 
172  bool checkTrajectory(double x, double y, double theta, double vx, double vy,
173  double vtheta, double vx_samp, double vy_samp, double vtheta_samp);
174 
188  double scoreTrajectory(double x, double y, double theta, double vx, double vy,
189  double vtheta, double vx_samp, double vy_samp, double vtheta_samp);
190 
201  bool getCellCosts(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost);
202 
204  void setFootprint( std::vector<geometry_msgs::Point> footprint ) { footprint_spec_ = footprint; }
205 
207  geometry_msgs::Polygon getFootprintPolygon() const { return costmap_2d::toPolygon(footprint_spec_); }
208  std::vector<geometry_msgs::Point> getFootprint() const { return footprint_spec_; }
209 
210  private:
224  Trajectory createTrajectories(double x, double y, double theta, double vx, double vy, double vtheta,
225  double acc_x, double acc_y, double acc_theta);
226 
244  void generateTrajectory(double x, double y, double theta, double vx, double vy,
245  double vtheta, double vx_samp, double vy_samp, double vtheta_samp, double acc_x, double acc_y,
246  double acc_theta, double impossible_cost, Trajectory& traj);
247 
255  double footprintCost(double x_i, double y_i, double theta_i);
256 
258 
259  MapGrid path_map_;
260  MapGrid goal_map_;
262  WorldModel& world_model_;
263 
264  std::vector<geometry_msgs::Point> footprint_spec_;
265 
266  std::vector<geometry_msgs::PoseStamped> global_plan_;
267 
268  bool stuck_left, stuck_right;
270 
272  bool strafe_right, strafe_left;
273 
274  bool escaping_;
275  bool meter_scoring_;
276 
277  double goal_x_,goal_y_;
278 
279  double final_goal_x_, final_goal_y_;
281 
282  double sim_time_;
283  double sim_granularity_;
284  double angular_sim_granularity_;
285 
286  int vx_samples_;
287  int vtheta_samples_;
288 
291 
292  double prev_x_, prev_y_;
294 
296 
298  double oscillation_reset_dist_;
300  bool holonomic_robot_;
301 
303 
304  double backup_vel_;
305 
306  bool dwa_;
310 
311  std::vector<double> y_vels_;
312 
313  double stop_time_buffer_;
314  double sim_period_;
315 
317 
318  boost::mutex configuration_mutex_;
319 
329  inline double computeNewXPosition(double xi, double vx, double vy, double theta, double dt){
330  return xi + (vx * cos(theta) + vy * cos(M_PI_2 + theta)) * dt;
331  }
332 
342  inline double computeNewYPosition(double yi, double vx, double vy, double theta, double dt){
343  return yi + (vx * sin(theta) + vy * sin(M_PI_2 + theta)) * dt;
344  }
345 
353  inline double computeNewThetaPosition(double thetai, double vth, double dt){
354  return thetai + vth * dt;
355  }
356 
357  //compute velocity based on acceleration
366  inline double computeNewVelocity(double vg, double vi, double a_max, double dt){
367  if((vg - vi) >= 0) {
368  return std::min(vg, vi + a_max * dt);
369  }
370  return std::max(vg, vi - a_max * dt);
371  }
372 
373  void getMaxSpeedToStopInTime(double time, double& vx, double& vy, double& vth){
374  vx = acc_lim_x_ * std::max(time, 0.0);
375  vy = acc_lim_y_ * std::max(time, 0.0);
376  vth = acc_lim_theta_ * std::max(time, 0.0);
377  }
378 
379  double lineCost(int x0, int x1, int y0, int y1);
380  double pointCost(int x, int y);
381  double headingDiff(int cell_x, int cell_y, double x, double y, double heading);
382  };
383 };
384 
385 #endif
base_local_planner::TrajectoryPlanner::checkTrajectory
bool checkTrajectory(double x, double y, double theta, double vx, double vy, double vtheta, double vx_samp, double vy_samp, double vtheta_samp)
Generate and score a single trajectory.
Definition: trajectory_planner.cpp:503
base_local_planner::TrajectoryPlanner::inscribed_radius_
double inscribed_radius_
Definition: trajectory_planner.h:351
base_local_planner::TrajectoryPlanner::occdist_scale_
double occdist_scale_
Scaling factors for the controller's cost function.
Definition: trajectory_planner.h:324
base_local_planner::TrajectoryPlanner::getFootprint
std::vector< geometry_msgs::Point > getFootprint() const
Definition: trajectory_planner.h:243
base_local_planner::TrajectoryPlanner::stop_time_buffer_
double stop_time_buffer_
How long before hitting something we're going to enforce that the robot stop.
Definition: trajectory_planner.h:348
base_local_planner::TrajectoryPlanner::~TrajectoryPlanner
~TrajectoryPlanner()
Destructs a trajectory controller.
Definition: trajectory_planner.cpp:191
base_local_planner::TrajectoryPlanner::min_in_place_vel_th_
double min_in_place_vel_th_
Velocity limits for the controller.
Definition: trajectory_planner.h:337
trajectory.h
base_local_planner::TrajectoryPlanner::computeNewVelocity
double computeNewVelocity(double vg, double vi, double a_max, double dt)
Compute velocity based on acceleration.
Definition: trajectory_planner.h:401
base_local_planner::TrajectoryPlanner::vtheta_samples_
int vtheta_samples_
The number of samples we'll take in the theta dimension of the control space.
Definition: trajectory_planner.h:322
base_local_planner::TrajectoryPlanner::createTrajectories
Trajectory createTrajectories(double x, double y, double theta, double vx, double vy, double vtheta, double acc_x, double acc_y, double acc_theta)
Create the trajectories we wish to explore, score them, and return the best option.
Definition: trajectory_planner.cpp:536
base_local_planner::TrajectoryPlanner::traj_one
Trajectory traj_one
Definition: trajectory_planner.h:330
base_local_planner::TrajectoryPlanner::strafe_left
bool strafe_left
Booleans to keep track of strafe direction for the robot.
Definition: trajectory_planner.h:307
base_local_planner::TrajectoryPlanner::getCellCosts
bool getCellCosts(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost)
Compute the components and total cost for a map grid cell.
Definition: trajectory_planner.cpp:193
base_local_planner::TrajectoryPlanner::path_distance_bias_
double path_distance_bias_
Definition: trajectory_planner.h:324
base_local_planner::TrajectoryPlanner::goal_map_
MapGrid goal_map_
The local map grid where we propagate goal distance.
Definition: trajectory_planner.h:295
base_local_planner::TrajectoryPlanner::escape_reset_dist_
double escape_reset_dist_
Definition: trajectory_planner.h:334
base_local_planner::TrajectoryPlanner::computeNewThetaPosition
double computeNewThetaPosition(double thetai, double vth, double dt)
Compute orientation based on velocity.
Definition: trajectory_planner.h:388
costmap_2d.h
footprint_helper.h
base_local_planner::TrajectoryPlanner::oscillation_reset_dist_
double oscillation_reset_dist_
The distance the robot must travel before it can explore rotational velocities that were unsuccessful...
Definition: trajectory_planner.h:333
base_local_planner::TrajectoryPlanner::escaping_
bool escaping_
Boolean to keep track of whether we're in escape mode.
Definition: trajectory_planner.h:309
base_local_planner::TrajectoryPlanner::stuck_right_strafe
bool stuck_right_strafe
Booleans to keep the robot from oscillating during strafing.
Definition: trajectory_planner.h:306
base_local_planner::TrajectoryPlanner::pointCost
double pointCost(int x, int y)
Definition: trajectory_planner.cpp:466
base_local_planner::TrajectoryPlanner::computeNewXPosition
double computeNewXPosition(double xi, double vx, double vy, double theta, double dt)
Compute x position based on velocity.
Definition: trajectory_planner.h:364
base_local_planner::TrajectoryPlanner::stuck_left
bool stuck_left
Definition: trajectory_planner.h:303
base_local_planner::TrajectoryPlanner::final_goal_y_
double final_goal_y_
The end position of the plan.
Definition: trajectory_planner.h:314
base_local_planner::TrajectoryPlanner::footprintCost
double footprintCost(double x_i, double y_i, double theta_i)
Checks the legality of the robot footprint at a position and orientation using the world model.
Definition: trajectory_planner.cpp:988
costmap_2d::Costmap2D
base_local_planner::TrajectoryPlanner::headingDiff
double headingDiff(int cell_x, int cell_y, double x, double y, double heading)
Definition: trajectory_planner.cpp:372
cost_values.h
base_local_planner::TrajectoryPlanner::footprint_helper_
base_local_planner::FootprintHelper footprint_helper_
Definition: trajectory_planner.h:292
base_local_planner::TrajectoryPlanner::sim_period_
double sim_period_
The number of seconds to use to compute max/min vels for dwa.
Definition: trajectory_planner.h:349
base_local_planner::TrajectoryPlanner::goal_distance_bias_
double goal_distance_bias_
Definition: trajectory_planner.h:324
base_local_planner::TrajectoryPlanner::prev_y_
double prev_y_
Used to calculate the distance the robot has traveled before reseting oscillation booleans.
Definition: trajectory_planner.h:327
base_local_planner::TrajectoryPlanner::getLocalGoal
void getLocalGoal(double &x, double &y)
Accessor for the goal the robot is currently pursuing in world corrdinates.
Definition: trajectory_planner.cpp:994
base_local_planner::TrajectoryPlanner::costmap_
const costmap_2d::Costmap2D & costmap_
Provides access to cost map information.
Definition: trajectory_planner.h:296
base_local_planner::TrajectoryPlanner::computeNewYPosition
double computeNewYPosition(double yi, double vx, double vy, double theta, double dt)
Compute y position based on velocity.
Definition: trajectory_planner.h:377
map_grid.h
base_local_planner::TrajectoryPlanner::escape_theta_
double escape_theta_
Used to calculate the distance the robot has traveled before reseting escape booleans.
Definition: trajectory_planner.h:328
base_local_planner::TrajectoryPlanner::final_goal_x_
double final_goal_x_
Definition: trajectory_planner.h:314
base_local_planner::TrajectoryPlanner::updatePlan
void updatePlan(const std::vector< geometry_msgs::PoseStamped > &new_plan, bool compute_dists=false)
Update the plan that the controller is following.
Definition: trajectory_planner.cpp:476
base_local_planner::TrajectoryPlanner::max_vel_th_
double max_vel_th_
Definition: trajectory_planner.h:337
base_local_planner::TrajectoryPlanner::goal_x_
double goal_x_
Definition: trajectory_planner.h:312
base_local_planner::TrajectoryPlanner::path_map_
MapGrid path_map_
The local map grid where we propagate path distance.
Definition: trajectory_planner.h:294
base_local_planner::TrajectoryPlanner::escape_y_
double escape_y_
Definition: trajectory_planner.h:328
base_local_planner::TrajectoryPlanner::angular_sim_granularity_
double angular_sim_granularity_
The distance between angular simulation points.
Definition: trajectory_planner.h:319
base_local_planner::TrajectoryPlanner::setFootprint
void setFootprint(std::vector< geometry_msgs::Point > footprint)
Set the footprint specification of the robot.
Definition: trajectory_planner.h:239
base_local_planner::TrajectoryPlanner::acc_lim_theta_
double acc_lim_theta_
The acceleration limits of the robot.
Definition: trajectory_planner.h:325
base_local_planner::TrajectoryPlanner::heading_lookahead_
double heading_lookahead_
How far the robot should look ahead of itself when differentiating between different rotational veloc...
Definition: trajectory_planner.h:332
base_local_planner::FootprintHelper
Definition: footprint_helper.h:85
base_local_planner::TrajectoryPlanner::world_model_
WorldModel & world_model_
The world model that the controller uses for collision detection.
Definition: trajectory_planner.h:297
base_local_planner::TrajectoryPlanner::scoreTrajectory
double scoreTrajectory(double x, double y, double theta, double vx, double vy, double vtheta, double vx_samp, double vy_samp, double vtheta_samp)
Generate and score a single trajectory.
Definition: trajectory_planner.cpp:519
base_local_planner::TrajectoryPlanner::circumscribed_radius_
double circumscribed_radius_
Definition: trajectory_planner.h:351
base_local_planner::TrajectoryPlanner::goal_y_
double goal_y_
Storage for the local goal the robot is pursuing.
Definition: trajectory_planner.h:312
base_local_planner::TrajectoryPlanner::sim_granularity_
double sim_granularity_
The distance between simulation points.
Definition: trajectory_planner.h:318
base_local_planner::TrajectoryPlanner::generateTrajectory
void generateTrajectory(double x, double y, double theta, double vx, double vy, double vtheta, double vx_samp, double vy_samp, double vtheta_samp, double acc_x, double acc_y, double acc_theta, double impossible_cost, Trajectory &traj)
Generate and score a single trajectory.
Definition: trajectory_planner.cpp:214
map_cell.h
base_local_planner::TrajectoryPlanner::getMaxSpeedToStopInTime
void getMaxSpeedToStopInTime(double time, double &vx, double &vy, double &vth)
Definition: trajectory_planner.h:408
base_local_planner::TrajectoryPlanner::final_goal_position_valid_
bool final_goal_position_valid_
True if final_goal_x_ and final_goal_y_ have valid data. Only false if an empty path is sent.
Definition: trajectory_planner.h:315
base_local_planner::TrajectoryPlanner::vx_samples_
int vx_samples_
The number of samples we'll take in the x dimenstion of the control space.
Definition: trajectory_planner.h:321
base_local_planner::TrajectoryPlanner::holonomic_robot_
bool holonomic_robot_
Is the robot holonomic or not?
Definition: trajectory_planner.h:335
base_local_planner::TrajectoryPlanner::findBestPath
Trajectory findBestPath(const geometry_msgs::PoseStamped &global_pose, geometry_msgs::PoseStamped &global_vel, geometry_msgs::PoseStamped &drive_velocities)
Given the current position, orientation, and velocity of the robot, return a trajectory to follow.
Definition: trajectory_planner.cpp:907
base_local_planner::TrajectoryPlanner::min_vel_x_
double min_vel_x_
Definition: trajectory_planner.h:337
base_local_planner::TrajectoryPlanner::getFootprintPolygon
geometry_msgs::Polygon getFootprintPolygon() const
Return the footprint specification of the robot.
Definition: trajectory_planner.h:242
base_local_planner::TrajectoryPlanner::TrajectoryPlanner
TrajectoryPlanner(WorldModel &world_model, const costmap_2d::Costmap2D &costmap, std::vector< geometry_msgs::Point > footprint_spec, double acc_lim_x=1.0, double acc_lim_y=1.0, double acc_lim_theta=1.0, double sim_time=1.0, double sim_granularity=0.025, int vx_samples=20, int vtheta_samples=20, double path_distance_bias=0.6, double goal_distance_bias=0.8, double occdist_scale=0.2, double heading_lookahead=0.325, double oscillation_reset_dist=0.05, double escape_reset_dist=0.10, double escape_reset_theta=M_PI_2, bool holonomic_robot=true, double max_vel_x=0.5, double min_vel_x=0.1, double max_vel_th=1.0, double min_vel_th=-1.0, double min_in_place_vel_th=0.4, double backup_vel=-0.1, bool dwa=false, bool heading_scoring=false, double heading_scoring_timestep=0.1, bool meter_scoring=true, bool simple_attractor=false, std::vector< double > y_vels=std::vector< double >(0), double stop_time_buffer=0.2, double sim_period=0.1, double angular_sim_granularity=0.025)
Constructs a trajectory controller.
Definition: trajectory_planner.cpp:142
base_local_planner::TrajectoryPlanner::heading_scoring_
bool heading_scoring_
Should we score based on the rollout approach or the heading approach.
Definition: trajectory_planner.h:342
base_local_planner::TrajectoryPlanner::escape_x_
double escape_x_
Definition: trajectory_planner.h:328
base_local_planner::TrajectoryPlanner::dwa_
bool dwa_
Should we use the dynamic window approach?
Definition: trajectory_planner.h:341
base_local_planner::TrajectoryPlanner::reconfigure
void reconfigure(BaseLocalPlannerConfig &cfg)
Reconfigures the trajectory planner.
Definition: trajectory_planner.cpp:61
base_local_planner::TrajectoryPlanner::max_vel_x_
double max_vel_x_
Definition: trajectory_planner.h:337
base_local_planner::TrajectoryPlanner::meter_scoring_
bool meter_scoring_
Definition: trajectory_planner.h:310
base_local_planner::Trajectory
Holds a trajectory generated by considering an x, y, and theta velocity.
Definition: trajectory.h:76
base_local_planner::TrajectoryPlanner::stuck_left_strafe
bool stuck_left_strafe
Definition: trajectory_planner.h:306
base_local_planner::TrajectoryPlanner::traj_two
Trajectory traj_two
Used for scoring trajectories.
Definition: trajectory_planner.h:330
base_local_planner::TrajectoryPlanner::y_vels_
std::vector< double > y_vels_
Y velocities to explore.
Definition: trajectory_planner.h:346
base_local_planner::TrajectoryPlanner::simple_attractor_
bool simple_attractor_
Enables simple attraction to a goal point.
Definition: trajectory_planner.h:344
base_local_planner::TrajectoryPlanner::acc_lim_x_
double acc_lim_x_
Definition: trajectory_planner.h:325
base_local_planner::TrajectoryPlanner::escape_reset_theta_
double escape_reset_theta_
The distance the robot must travel before it can leave escape mode.
Definition: trajectory_planner.h:334
base_local_planner::TrajectoryPlanner::backup_vel_
double backup_vel_
The velocity to use while backing up.
Definition: trajectory_planner.h:339
base_local_planner::TrajectoryPlanner::min_vel_th_
double min_vel_th_
Definition: trajectory_planner.h:337
base_local_planner::TrajectoryPlanner::rotating_right
bool rotating_right
Booleans to keep track of the direction of rotation for the robot.
Definition: trajectory_planner.h:304
base_local_planner
Definition: costmap_model.h:44
base_local_planner::TrajectoryPlanner::lineCost
double lineCost(int x0, int x1, int y0, int y1)
Definition: trajectory_planner.cpp:389
base_local_planner::TrajectoryPlanner::sim_time_
double sim_time_
The number of seconds each trajectory is "rolled-out".
Definition: trajectory_planner.h:317
base_local_planner::TrajectoryPlanner::heading_scoring_timestep_
double heading_scoring_timestep_
How far to look ahead in time when we score a heading.
Definition: trajectory_planner.h:343
base_local_planner::TrajectoryPlanner::global_plan_
std::vector< geometry_msgs::PoseStamped > global_plan_
The global path for the robot to follow.
Definition: trajectory_planner.h:301
base_local_planner::TrajectoryPlanner::configuration_mutex_
boost::mutex configuration_mutex_
Definition: trajectory_planner.h:353
base_local_planner::TrajectoryPlanner::TrajectoryPlannerTest
friend class TrajectoryPlannerTest
Definition: trajectory_planner.h:102
base_local_planner::TrajectoryPlanner::strafe_right
bool strafe_right
Definition: trajectory_planner.h:307
base_local_planner::TrajectoryPlanner::footprint_spec_
std::vector< geometry_msgs::Point > footprint_spec_
The footprint specification of the robot.
Definition: trajectory_planner.h:299
base_local_planner::TrajectoryPlanner::rotating_left
bool rotating_left
Definition: trajectory_planner.h:304
costmap_2d::toPolygon
geometry_msgs::Polygon toPolygon(std::vector< geometry_msgs::Point > pts)
base_local_planner::TrajectoryPlanner::acc_lim_y_
double acc_lim_y_
Definition: trajectory_planner.h:325
world_model.h
base_local_planner::TrajectoryPlanner::prev_x_
double prev_x_
Definition: trajectory_planner.h:327
base_local_planner::TrajectoryPlanner::stuck_right
bool stuck_right
Booleans to keep the robot from oscillating during rotation.
Definition: trajectory_planner.h:303


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:24