file
Geo.h
Namespaces
Classes
- struct esp::geo::Ray
Enums
- enum class ColorSpace { RGBA, sRGBA, HSV, XYZ }
- This enum describes the various colorspaces that colors in Habitat can occupy. This is currently governed by the supported color space conversions built into the Magnum Color types. This is provided for easy user access to these conversion mechansims.
Functions
-
auto convexHull2D(const std::
vector<vec2f>& points) -> std:: vector<vec2f> -
auto getTransformedBB(const Magnum::
Range3D& range, const Magnum:: Matrix4& xform) -> Magnum:: Range3D - Compute the axis-aligned bounding box which results from applying a transform to an existing bounding box.
-
auto getPointDistsAlongTrajectory(const std::
vector<Mn:: Vector3>& pts) -> std:: vector<float> - Return a vector of L2/Euclidean distances of points along a trajectory. First point will always be 0, and last point will give length of trajectory.
-
auto interp2Points(const Mn::
Vector3& a, float ta, const Mn:: Vector3& b, float tb, float t) -> Mn:: Vector3 - Interpolate between two points to find a third at a specified t between them.
-
auto calcWeightedDistance(const Mn::
Vector3& a, const Mn:: Vector3& b, float alpha = .5f) -> float - Determine the weighted distance of point b from point a. Used to derive relative knot value for point b as a function of distance from point a for Catmull-Rom spline derivation.
-
auto buildCatmullRomTrajOfPoints(const std::
vector<Mn:: Vector3>& pts, int numInterp, float alpha = .5f) -> std:: vector<Mn:: Vector3> - Build a smooth trajectory of interpolated points from key points along a path using Catmull-Rom Spline of type determined by chosen alpha.
-
auto buildTrajectoryTubeSolid(const std::
vector<Mn:: Vector3>& pts, const std:: vector<Mn:: Color3>& interpColors, int numSegments, float radius, bool smooth, int numInterp, ColorSpace clrSpace = ColorSpace::HSV) -> Mn::Trade::MeshData - Build a mesh representing a tube of given radius around the trajectory given by the passed points. Will either build cylinders between each pair of points in pts, or between sequential points in a smoothed trajectory derived using centripetal Catmull-Rom spline between points in pts.
-
auto getColorAsString(const Magnum::
Color3ub& color) -> std:: string - Returns a nicely formatted hex string representation of
color
. -
template<class T>auto getValueAsUInt(T color) -> uint32_
t - Return an unsigned int encoding of passed
color
value. -
auto getValueAsUInt(const Mn::
Color3ub& color) -> uint32_ t - Return an unsigned int encoding of passed
color
for type Mn::Color3ub. -
auto getValueAsUInt(const Mn::
Color4ub& color) -> uint32_ t - Return an unsigned int encoding of passed
color
for type Mn::Color4ub. -
auto getValueAsUInt(int color) -> uint32_
t - Return an unsigned int encoding of passed
color
for type int - provided to support vector of per-vertex IDs . -
auto buildAdjList(int numVerts,
const std::
vector<uint32_ t>& indexBuffer) -> std:: vector<std:: set<uint32_ t>> - Build an adjacency list using the passed index buffer. Assumes each sequence of 3 indices describesd a poly.
-
template<class T>void conditionalDFS(const std::
vector<std:: set<uint32_ t>>& adjList, const std:: vector<T>& clrVec, uint32_ t vIDX, std:: vector<bool>& visited, const T& clr, std:: set<uint32_ t>& setOfVerts) - Build a connected component recursively on an unconnected graph (i.e. mesh vertices), building from passed
vIDX
from adjecent verts that match the passedclr
value, which can be any per-vertex identifier or tag. -
template<class T>auto findCCsByGivenColor(const std::
vector<std:: set<uint32_ t>>& adjList, const std:: vector<T>& clrVec) -> std:: unordered_map<uint32_ t, std:: vector<std:: set<uint32_ t>>> - Find and return all connected components in a graph (represented by the
adjList
), that match some specified per-vertex tag/"color". -
template<typename T>auto clamp(const T& n, const T& low, const T& high) -> T
Variables
Enum documentation
enum class ColorSpace
This enum describes the various colorspaces that colors in Habitat can occupy. This is currently governed by the supported color space conversions built into the Magnum Color types. This is provided for easy user access to these conversion mechansims.
Enumerators | |
---|---|
RGBA |
|
sRGBA |
|
HSV |
HSV represent Hue, Saturation and Value, where the color space is modeled on a cylinder, hue is an angle, saturation is a radius and value is measured along the height of the cylinder. |
XYZ |
CIE XYZ, where Y is luminance, and x-z plane describes chromaticity. |
Function documentation
Magnum:: Range3D getTransformedBB(const Magnum:: Range3D& range,
const Magnum:: Matrix4& xform)
Compute the axis-aligned bounding box which results from applying a transform to an existing bounding box.
Parameters | |
---|---|
range | The initial axis-aligned bounding box. |
xform | The desired transform to apply. |
Returns | The resulting, transformed axis-aligned bounding box. |
std:: vector<float> getPointDistsAlongTrajectory(const std:: vector<Mn:: Vector3>& pts)
Return a vector of L2/Euclidean distances of points along a trajectory. First point will always be 0, and last point will give length of trajectory.
Parameters | |
---|---|
pts | Vector of points along trajectory. |
Mn:: Vector3 interp2Points(const Mn:: Vector3& a,
float ta,
const Mn:: Vector3& b,
float tb,
float t)
Interpolate between two points to find a third at a specified t between them.
Parameters | |
---|---|
a | first point |
ta | a 's time along trajectory |
b | second point |
tb | b 's time along trajectory |
t | the time along the trajectory for the desired point |
Returns | the interpolated point at time t |
float calcWeightedDistance(const Mn:: Vector3& a,
const Mn:: Vector3& b,
float alpha = .5f)
Determine the weighted distance of point b from point a. Used to derive relative knot value for point b as a function of distance from point a for Catmull-Rom spline derivation.
Parameters | |
---|---|
a | a point whose knot value is known |
b | a point whose knot value is unkknown |
alpha | Exponent for distance calculation used to derive time parameter for splines. Determines nature of resultant CR spline. 0 yields a standard uniform Catmull-Rom spline (which may have cusps), .5 yields centrepital CR spline, 1.0 yields chordal CR spline. Default is .5. Use alpha == 1.0f for L2 distance calc. |
Returns | b's knot valute relative to a / distance from a |
std:: vector<Mn:: Vector3> buildCatmullRomTrajOfPoints(const std:: vector<Mn:: Vector3>& pts,
int numInterp,
float alpha = .5f)
Build a smooth trajectory of interpolated points from key points along a path using Catmull-Rom Spline of type determined by chosen alpha.
Parameters | |
---|---|
pts | The key points of the trajectory |
numInterp | The number of interpolations between each trajectory point |
alpha | Exponent for distance calculation used to derive time parameter. Determines nature of resultant CR spline. 0 yields a standard uniform Catmull-Rom spline (which may have cusps), .5 yields centrepital CR spline, 1.0 yields chordal CR spline. Default is .5. |
Returns | interpolated points for trajectory |
Mn::Trade::MeshData buildTrajectoryTubeSolid(const std:: vector<Mn:: Vector3>& pts,
const std:: vector<Mn:: Color3>& interpColors,
int numSegments,
float radius,
bool smooth,
int numInterp,
ColorSpace clrSpace = ColorSpace::HSV)
Build a mesh representing a tube of given radius around the trajectory given by the passed points. Will either build cylinders between each pair of points in pts, or between sequential points in a smoothed trajectory derived using centripetal Catmull-Rom spline between points in pts.
Parameters | |
---|---|
pts | The key points of the trajectory, in order |
interpColors | The list of one or more colors to assign in sequence to vertices along the length of the tube, interpolating if necessary. |
numSegments | The number of segments around the circumference of the tube. |
radius | The radius of the tube |
smooth | Whether to smooth the points or not |
numInterp | The number of interpolations between each trajectory point, if smoothing |
clrSpace | The color space to interpolate the given colrs in |
Returns | The resultant meshdata for the tube |
std:: string getColorAsString(const Magnum:: Color3ub& color)
Returns a nicely formatted hex string representation of color
.
Parameters | |
---|---|
color | Color to build string from. |
std:: vector<std:: set<uint32_ t>> buildAdjList(int numVerts,
const std:: vector<uint32_ t>& indexBuffer)
Build an adjacency list using the passed index buffer. Assumes each sequence of 3 indices describesd a poly.
Parameters | |
---|---|
numVerts | Number of verts found in mesh. |
indexBuffer | |
Returns | vector of sets, where each set's index corresponds to the src vert in the vertex buffer, and each element is a set containing the indices of the adjacent verts. |
template<class T>
void conditionalDFS(const std:: vector<std:: set<uint32_ t>>& adjList,
const std:: vector<T>& clrVec,
uint32_ t vIDX,
std:: vector<bool>& visited,
const T& clr,
std:: set<uint32_ t>& setOfVerts)
Build a connected component recursively on an unconnected graph (i.e. mesh vertices), building from passed vIDX
from adjecent verts that match the passed clr
value, which can be any per-vertex identifier or tag.
Parameters | |
---|---|
adjList | A reference to the mesh's adjacency list. IDX of list is src vert index in owning vert list, value is dest vert index in vert list. |
clrVec | A reference to the per-vertex identifiers used to condition the CC (not necessarily a color). |
vIDX | The index of the src vertex of this part of the CC. |
visited | Per-vertex visitation record. |
clr | The CC's identifying "color"/tag, to be matched by adjacent verts for membership in CC. |
setOfVerts | Aggregation of verts in the CC. |
template<class T>
std:: unordered_map<uint32_ t, std:: vector<std:: set<uint32_ t>>> findCCsByGivenColor(const std:: vector<std:: set<uint32_ t>>& adjList,
const std:: vector<T>& clrVec)
Find and return all connected components in a graph (represented by the adjList
), that match some specified per-vertex tag/"color".
Parameters | |
---|---|
adjList | A reference to the mesh's per-vertex adjacency list. IDX of list is src vert index in owning vert list, value is dest vert index in vert list. |
clrVec | A reference to the per-vertex identifiers used to condition the CC (not necessarily a color). |
Returns | an unordered map, keyed by tag/color value encoded as int, where the value is a vector of all sets of CCs consisting of verts with specified tag/"color". |