Public Member Functions | Static Public Member Functions | Protected Attributes | Static Protected Attributes | List of all members
gtsam::SimPolygon2D Class Reference

#include <SimPolygon2D.h>

Public Member Functions

bool contains (const Point2 &p) const
 
bool equals (const SimPolygon2D &p, double tol=1e-5) const
 
const Point2landmark (size_t i) const
 
bool overlaps (const SimPolygon2D &p) const
 
void print (const std::string &s="") const
 
 SimPolygon2D ()
 
size_t size () const
 
const Point2Vectorvertices () const
 
std::vector< SimWall2Dwalls () const
 

Static Public Member Functions

static bool anyContains (const Point2 &p, const std::vector< SimPolygon2D > &obstacles)
 
static bool anyOverlaps (const SimPolygon2D &p, const std::vector< SimPolygon2D > &obstacles)
 
static SimPolygon2D createRectangle (const Point2 &p, double height, double width)
 
static SimPolygon2D createTriangle (const Point2 &pA, const Point2 &pB, const Point2 &pC)
 
static bool insideBox (double s, const Point2 &p)
 
static bool nearExisting (const Point2Vector &S, const Point2 &p, double threshold)
 
static Rot2 randomAngle ()
 
static Point2 randomBoundedPoint2 (double boundary_size, const Point2Vector &landmarks, double min_landmark_dist)
 
static Point2 randomBoundedPoint2 (double boundary_size, const Point2Vector &landmarks, const std::vector< SimPolygon2D > &obstacles, double min_landmark_dist)
 
static Point2 randomBoundedPoint2 (double boundary_size, const std::vector< SimPolygon2D > &obstacles)
 
static Point2 randomBoundedPoint2 (const Point2 &LL_corner, const Point2 &UR_corner, const Point2Vector &landmarks, const std::vector< SimPolygon2D > &obstacles, double min_landmark_dist)
 
static double randomDistance (double mu, double sigma, double min_dist=-1.0)
 
static Pose2 randomFreePose (double boundary_size, const std::vector< SimPolygon2D > &obstacles)
 
static Point2 randomPoint2 (double s)
 
static SimPolygon2D randomRectangle (double side_len, double mean_side_len, double sigma_side_len, double min_vertex_dist, double min_side_len, const std::vector< SimPolygon2D > &existing_polys)
 
static SimPolygon2D randomTriangle (double side_len, double mean_side_len, double sigma_side_len, double min_vertex_dist, double min_side_len, const std::vector< SimPolygon2D > &existing_polys)
 
static void seedGenerator (unsigned long seed)
 

Protected Attributes

Point2Vector landmarks_
 

Static Protected Attributes

static std::minstd_rand rng
 

Detailed Description

General polygon class for convex polygons

Definition at line 20 of file SimPolygon2D.h.

Constructor & Destructor Documentation

gtsam::SimPolygon2D::SimPolygon2D ( )
inline

Don't use this constructor, use a named one instead

Definition at line 28 of file SimPolygon2D.h.

Member Function Documentation

bool gtsam::SimPolygon2D::anyContains ( const Point2 p,
const std::vector< SimPolygon2D > &  obstacles 
)
static

returns true iff p is contained in any of a set of polygons

Definition at line 106 of file SimPolygon2D.cpp.

bool gtsam::SimPolygon2D::anyOverlaps ( const SimPolygon2D p,
const std::vector< SimPolygon2D > &  obstacles 
)
static

returns true iff polygon p overlaps with any of a set of polygons

Definition at line 114 of file SimPolygon2D.cpp.

bool gtsam::SimPolygon2D::contains ( const Point2 p) const

Core function for randomly generating scenarios. Polygons are closed, convex shapes.

Returns
true if the given point is contained by this polygon

Definition at line 68 of file SimPolygon2D.cpp.

SimPolygon2D gtsam::SimPolygon2D::createRectangle ( const Point2 p,
double  height,
double  width 
)
static

Named constructor for creating axis-aligned rectangles

Parameters
pis the lower-left corner

Definition at line 33 of file SimPolygon2D.cpp.

SimPolygon2D gtsam::SimPolygon2D::createTriangle ( const Point2 pA,
const Point2 pB,
const Point2 pC 
)
static

Named constructor for creating triangles

Definition at line 24 of file SimPolygon2D.cpp.

bool gtsam::SimPolygon2D::equals ( const SimPolygon2D p,
double  tol = 1e-5 
) const

Definition at line 43 of file SimPolygon2D.cpp.

bool gtsam::SimPolygon2D::insideBox ( double  s,
const Point2 p 
)
static

returns true iff p is inside a square centered at zero with side s

Definition at line 312 of file SimPolygon2D.cpp.

const Point2& gtsam::SimPolygon2D::landmark ( size_t  i) const
inline

Definition at line 59 of file SimPolygon2D.h.

bool gtsam::SimPolygon2D::nearExisting ( const Point2Vector S,
const Point2 p,
double  threshold 
)
static

returns true iff p is within threshold of any point in S

Definition at line 317 of file SimPolygon2D.cpp.

bool gtsam::SimPolygon2D::overlaps ( const SimPolygon2D p) const

Checks two polygons to determine if they overlap

Returns
true iff at least one vertex of one polygon is contained in the other

Definition at line 95 of file SimPolygon2D.cpp.

void gtsam::SimPolygon2D::print ( const std::string &  s = "") const

Definition at line 52 of file SimPolygon2D.cpp.

Rot2 gtsam::SimPolygon2D::randomAngle ( )
static

randomly generate a Rot2 with a uniform distribution over theta

Definition at line 230 of file SimPolygon2D.cpp.

Point2 gtsam::SimPolygon2D::randomBoundedPoint2 ( double  boundary_size,
const Point2Vector landmarks,
double  min_landmark_dist 
)
static

pick a random point within a box that is further than dist d away from existing landmarks

Definition at line 264 of file SimPolygon2D.cpp.

Point2 gtsam::SimPolygon2D::randomBoundedPoint2 ( double  boundary_size,
const Point2Vector landmarks,
const std::vector< SimPolygon2D > &  obstacles,
double  min_landmark_dist 
)
static

pick a random point within a box that meets above requirements, as well as staying out of obstacles

Definition at line 276 of file SimPolygon2D.cpp.

Point2 gtsam::SimPolygon2D::randomBoundedPoint2 ( double  boundary_size,
const std::vector< SimPolygon2D > &  obstacles 
)
static

pick a random point that only avoid obstacles

Definition at line 252 of file SimPolygon2D.cpp.

Point2 gtsam::SimPolygon2D::randomBoundedPoint2 ( const Point2 LL_corner,
const Point2 UR_corner,
const Point2Vector landmarks,
const std::vector< SimPolygon2D > &  obstacles,
double  min_landmark_dist 
)
static

pick a random point in box defined by lower left and upper right corners

Definition at line 289 of file SimPolygon2D.cpp.

double gtsam::SimPolygon2D::randomDistance ( double  mu,
double  sigma,
double  min_dist = -1.0 
)
static

generate a distance from a normal distribution given a mean and sigma

Definition at line 237 of file SimPolygon2D.cpp.

Pose2 gtsam::SimPolygon2D::randomFreePose ( double  boundary_size,
const std::vector< SimPolygon2D > &  obstacles 
)
static

pick a random pose in a bounded area that is not in an obstacle

Definition at line 307 of file SimPolygon2D.cpp.

Point2 gtsam::SimPolygon2D::randomPoint2 ( double  s)
static

pick a random point uniformly over a box of side s

Definition at line 224 of file SimPolygon2D.cpp.

SimPolygon2D gtsam::SimPolygon2D::randomRectangle ( double  side_len,
double  mean_side_len,
double  sigma_side_len,
double  min_vertex_dist,
double  min_side_len,
const std::vector< SimPolygon2D > &  existing_polys 
)
static

Randomly generate a rectangle that does not conflict with others Uniformly distributed over box area, with normally distributed lengths of edges THROWS: std::runtime_error if can't find a position

Definition at line 177 of file SimPolygon2D.cpp.

SimPolygon2D gtsam::SimPolygon2D::randomTriangle ( double  side_len,
double  mean_side_len,
double  sigma_side_len,
double  min_vertex_dist,
double  min_side_len,
const std::vector< SimPolygon2D > &  existing_polys 
)
static

Randomly generate a triangle that does not conflict with others Uniformly distributed over box area, with normally distributed lengths of edges THROWS: std::runtime_error if can't find a position

Definition at line 122 of file SimPolygon2D.cpp.

void gtsam::SimPolygon2D::seedGenerator ( unsigned long  seed)
static

seed the random number generator - only needs to be done once

Definition at line 19 of file SimPolygon2D.cpp.

size_t gtsam::SimPolygon2D::size ( ) const
inline

Definition at line 60 of file SimPolygon2D.h.

const Point2Vector& gtsam::SimPolygon2D::vertices ( ) const
inline

Definition at line 61 of file SimPolygon2D.h.

vector< SimWall2D > gtsam::SimPolygon2D::walls ( ) const

Get a set of walls along the edges

Definition at line 59 of file SimPolygon2D.cpp.

Member Data Documentation

Point2Vector gtsam::SimPolygon2D::landmarks_
protected

Definition at line 22 of file SimPolygon2D.h.

std::minstd_rand gtsam::SimPolygon2D::rng
staticprotected

Definition at line 23 of file SimPolygon2D.h.


The documentation for this class was generated from the following files:


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:58:29