Menge Plugin Examples
A Collection of Example Plugins for the Menge Framework
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Pages
Public Member Functions | Protected Attributes | List of all members
GCF::Ellipse Class Reference

Definition of an ellipse. More...

#include <Ellipse.h>

Public Member Functions

 Ellipse ()
 Basic constructor with default values. More...
 
 Ellipse (const Vector2 &center)
 Constructor with ellipse center definition. More...
 
 Ellipse (const Vector2 &center, const Vector2 &axes)
 Constructor with ellipse center definition and axes. More...
 
 Ellipse (const Vector2 &center, const Vector2 &axes, float angle)
 Constructor with ellipse center definition, axes, and orientation. More...
 
float ellipseCenterDistance (const Ellipse &other) const
 Compute the distance between the centers of this ellipse and the provided ellipse. More...
 
Vector2 ellipseCenterDisplace (const Ellipse &other) const
 Computes the displacement from this ellipse's center to the other ellipse's center. More...
 
float distanceOfClosestApproach (const Ellipse &other) const
 Compute the distance of closest approach between two ellipses. More...
 
float approxDistanceOfClosestApproach (const Ellipse &other) const
 Compute the effective distance between this ellipse and the provided ellipse. More...
 
Vector2 closestPoint (const Vector2 &pt) const
 Computes the closest point on the ellipse to a point Also reports direction. More...
 
float minimumDistance (const Agents::Obstacle *obstacle, Vector2 &dir) const
 Computes the minimum distance between the obstacle (a line segment) and the ellipse. More...
 
float distanceOfClosestApproach (const Agents::Obstacle *line) const
 Computes the distance of closest approach. More...
 
float approximateMinimumDistance (const Vector2 &pt) const
 Computes the approximate distance from point p to the ellipse. More...
 
float radiusInPointDirection (const Vector2 &pt) const
 Computes the radius of the ellipse in the direction of the point. More...
 
Vector2 toEllipseSpace (const Vector2 &pt) const
 Translates the point into ellipse-space coordinates i.e. the transformation necessary to place the ellipse at the center, with its axes aligned with the world axes. More...
 
Vector2 fromEllipseSpace (const Vector2 &pt) const
 Translates the point from ellipse-space coordinates into world coordinates. More...
 
void setOrientation (float angle)
 Sets the orientation of the ellipse. More...
 
void setOrientation (const Vector2 &dir)
 Sets the orientation of the ellipse. More...
 
void setCenter (const Vector2 &pos)
 Set center of the ellipse. More...
 
void setAxes (const Vector2 &axes)
 Sets the major and minor axes of the ellipse. More...
 
void setAxes (float major, float minor)
 Sets the major and minor axes of the ellipse. More...
 
void setMajorAxis (float length)
 Sets the major axis of the ellipse. More...
 
float getMajor () const
 Returns the length of the major axis. More...
 
void setMinorAxis (float length)
 Sets the minor axis of the ellipse. More...
 
float getMinor () const
 Returns the length of the minor axis. More...
 
float getSmallerAxis () const
 Returns the smaller of the axes.
 
float getLargerAxis () const
 Returns the larger of the axes.
 

Protected Attributes

Vector2 _center
 The center of the ellipse.
 
float _cosPhi
 Part of the orientation of the ellipse. Oriented with angle phi. This is cosine of that angle.
 
float _sinPhi
 Part of the orientation of the ellipse. Oriented with angle phi. This is sine of that angle.
 
float _majorAxis
 Length of semi-major axis. The semi-major axis is the "direction" the ellipse is oriented. So, when phi is zero, the semi-major axis is aligned with the x-axis. It need not be a bigger value than the semi-minor axis.
 
float _minorAxis
 Length of semi-minor axis. The semi-minor axis is perpendicular to the "direction" the ellipse is oriented. So, when phi is zero, the semi-minor axis is aligned with the y-axis. It need not be a smaller value than the semi-major axis.
 

Detailed Description

Definition of an ellipse.

Constructor & Destructor Documentation

GCF::Ellipse::Ellipse ( )

Basic constructor with default values.

By default, the Ellipse is a circle, centered on the origin.

GCF::Ellipse::Ellipse ( const Vector2 &  center)

Constructor with ellipse center definition.

Parameters
centerThe position of the ellipse's center in R2.
GCF::Ellipse::Ellipse ( const Vector2 &  center,
const Vector2 &  axes 
)

Constructor with ellipse center definition and axes.

Parameters
centerThe position of the ellipse's center in R2.
axesThe semi-major and semi-minor axis values stored in a two-dimensional vector.
GCF::Ellipse::Ellipse ( const Vector2 &  center,
const Vector2 &  axes,
float  angle 
)

Constructor with ellipse center definition, axes, and orientation.

Parameters
centerThe position of the ellipse's center in R2.
axesThe semi-major and semi-minor axis values stored in a two-dimensional vector.
angleThe angle (in radians) defining the orientation of the ellipse.

Member Function Documentation

float GCF::Ellipse::approxDistanceOfClosestApproach ( const Ellipse other) const

Compute the effective distance between this ellipse and the provided ellipse.

Effective distance is the distance between two ellipse boundaries along the line that connects the ellipse centers.

Parameters
otherThe other ellipse
Returns
The effective distance.
float GCF::Ellipse::approximateMinimumDistance ( const Vector2 &  pt) const

Computes the approximate distance from point p to the ellipse.

This is computed by finding the intersection of a line formed by the point and the origin with the ellipse. The distance is to that point. This is NOT the ACTUAL closest distance.

Parameters
ptThe point whose distance is to be computed.
Returns
A positive value if pt is outside the ellipse and a negative value if the point lies inside the ellipse.
Vector2 GCF::Ellipse::closestPoint ( const Vector2 &  pt) const

Computes the closest point on the ellipse to a point Also reports direction.

Parameters
ptThe point to which we want the closest point.
Returns
The point on the ellipse that was closest.
float GCF::Ellipse::distanceOfClosestApproach ( const Ellipse other) const

Compute the distance of closest approach between two ellipses.

Parameters
otherThe other ellipse
Returns
The distance of closest approach.
float GCF::Ellipse::distanceOfClosestApproach ( const Agents::Obstacle *  line) const

Computes the distance of closest approach.

It is the distance between the center and the line after the obstacle has been moved along its normal until it makes contact. The obstacle is interpreted as an INFINITE line

Parameters
lineThe line segment obstacle to compute against.
Returns
float representing the "distance of closest approach"
Vector2 GCF::Ellipse::ellipseCenterDisplace ( const Ellipse other) const
inline

Computes the displacement from this ellipse's center to the other ellipse's center.

Parameters
otherThe other ellipse
Returns
The center displacement.
float GCF::Ellipse::ellipseCenterDistance ( const Ellipse other) const
inline

Compute the distance between the centers of this ellipse and the provided ellipse.

Parameters
otherThe other ellipse
Returns
The center distance.
Vector2 GCF::Ellipse::fromEllipseSpace ( const Vector2 &  pt) const

Translates the point from ellipse-space coordinates into world coordinates.

Parameters
ptThe point to translate.
Returns
The translated point.
float GCF::Ellipse::getMajor ( ) const
inline

Returns the length of the major axis.

Returns
The major axis
float GCF::Ellipse::getMinor ( ) const
inline

Returns the length of the minor axis.

Returns
The major axis
float GCF::Ellipse::minimumDistance ( const Agents::Obstacle *  obstacle,
Vector2 &  dir 
) const

Computes the minimum distance between the obstacle (a line segment) and the ellipse.

Also provides the direction of that minimum displacement.

Parameters
obstacleA pointer to the obstacle to test
dirThe direction of minimum displacment is set into this parameter.
Returns
The distance (in dir) from the nearest point on the obstacle to the ellipse.
float GCF::Ellipse::radiusInPointDirection ( const Vector2 &  pt) const

Computes the radius of the ellipse in the direction of the point.

Parameters
ptThe point used to define the direction. Should be different from the ellipse center and, ideally, outside the ellipse.
Returns
The length of the radius in this direction
void GCF::Ellipse::setAxes ( const Vector2 &  axes)
inline

Sets the major and minor axes of the ellipse.

Parameters
axesA two dimensional vector containg the major and minor axis sizes in the x and y values, respectively.
void GCF::Ellipse::setAxes ( float  major,
float  minor 
)
inline

Sets the major and minor axes of the ellipse.

Parameters
majorThe value of the semi-major axis.
minorThe value of the semi-minor axis.
void GCF::Ellipse::setCenter ( const Vector2 &  pos)
inline

Set center of the ellipse.

Parameters
posThe two-dimensional vector specifying center position.
void GCF::Ellipse::setMajorAxis ( float  length)
inline

Sets the major axis of the ellipse.

Parameters
lengthThe value of the semi-major axis.
void GCF::Ellipse::setMinorAxis ( float  length)
inline

Sets the minor axis of the ellipse.

Parameters
lengthThe value of the semi-minor axis.
void GCF::Ellipse::setOrientation ( float  angle)
inline

Sets the orientation of the ellipse.

Parameters
angleRotation from x-axis in radians.
void GCF::Ellipse::setOrientation ( const Vector2 &  dir)
inline

Sets the orientation of the ellipse.

Parameters
dirA unit-length vector pointing in the direction
Vector2 GCF::Ellipse::toEllipseSpace ( const Vector2 &  pt) const

Translates the point into ellipse-space coordinates i.e. the transformation necessary to place the ellipse at the center, with its axes aligned with the world axes.

Parameters
ptThe point to translate.
Returns
The translated point.

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