FOUND
Loading...
Searching...
No Matches
found Namespace Reference

Classes

union  _d_u_
 Union for converting a 64-bit floating point number from host byte order to network byte order and vice versa. More...
 
union  _f_u_
 Union for converting a 32-bit floating point number from host byte order to network byte order and vice versa. More...
 
class  Action
 Action is an interface that wraps a function that does something. More...
 
class  ApproximateOrbitPropagationAlgorithm
 OrbitPropagationAlgorithm is a stage that propagates an orbit over a specified time period. More...
 
class  Attitude
 An Attitude is an immutable object that represents the orientation of a 3D point. More...
 
class  CalibrationAlgorithm
 The CalibrationAlgorithm is an interface for algorithms that calibrate our orientation to the reference orientation. More...
 
class  CalibrationPipelineExecutor
 CalibrationPipelineExecutor is the pipeline executor for the calibration pipeline. More...
 
class  Camera
 A Camera is a mutable object that represents a Camera. More...
 
struct  Component
 Represents a connected component in an image. More...
 
struct  DataFile
 Represents a complete serialized data file. More...
 
struct  DataFileHeader
 Represents the header of a data file used in the serialization process. More...
 
struct  DateTime
 DateTime represents a date and time. More...
 
class  DistanceDeterminationAlgorithm
 The DistanceDeterminationAlgorithm class houses the Distance Determination Algorithm. More...
 
class  DistancePipelineExecutor
 DistancePipelineExecutor is the pipeline executor for the distance determination pipeline. More...
 
struct  EarthSphericalVec3
 Represents an Earth-centric Spherical Vector with time information. More...
 
struct  Edge
 Represents a 2D edge in an image. More...
 
class  EdgeDetectionAlgorithm
 The EdgeDetection Algorithm class houses the Edge Detection Algorithm. More...
 
class  EllipticDistanceDeterminationAlgorithm
 The DistanceDeterminationAlgorithm class houses the Distance Determination Algorithm. More...
 
class  EulerAngles
 An EulerAngle is a mutable Object representing Euler Angles of a 3D point. More...
 
class  FeatureDetectionVectorGenerationAlgorithm
 FeatureDetectionVectorGenerationAlgorithm figures out the distance vector of the satellite relative to earth by identifying features on earth. More...
 
struct  Image
 Represents an image. More...
 
class  IterativeSphericalDistanceDeterminationAlgorithm
 The IterativeSphericalDistanceDeterminationAlgorithm is a variation of the SphericalDistanceDeterminationAlgorithm algorithm in that it runs it repeatedly to use all the points given to it. More...
 
struct  LocationRecord
 Represents a single spatial data point with position and timestamp. More...
 
class  LoCEdgeDetectionAlgorithm
 The LoGEdgeDetection Algorithm class houses the Edge Detection Algorithm. More...
 
class  LOSTCalibrationAlgorithm
 The LostCalibrationAlgorithm class houses the calibration algorithm that uses the orientation information from LOST to calibrate the camera's local orientation with the reference orientation (i.e. More...
 
class  LOSTVectorGenerationAlgorithm
 The LOSTVectorGenerationAlgorithm class houses the a Vector Assembly Algorithm that calculates the position of the satellite using orientation information determined from LOST. More...
 
class  Mat3
 A Mat3 is a mutable object that represents a 3x3 Matrix. More...
 
struct  OrbitParams
 OrbitParams defines the orbital parameters of a given orbit. More...
 
class  OrbitPipelineExecutor
 OrbitPipelineExecutor is the pipeline executor for the orbit determination pipeline. More...
 
class  OrbitPropagationAlgorithm
 The OrbitPropagationAlgorithm is an algorithm that propagates an orbit over a specified time period. More...
 
class  Pipeline
 Pipeline is composite Stage (i.e. More...
 
class  PipelineExecutor
 PipelineExecutor is an interface for classes that execute complex pipelines. More...
 
class  Quaternion
 A Quaternion is a mutable object that represents a Quaternion. More...
 
class  SimpleEdgeDetectionAlgorithm
 The SimpleEdgeDetection Algorithm class houses the Edge Detection Algorithm. More...
 
class  SphericalDistanceDeterminationAlgorithm
 The DistanceDeterminationAlgorithm class houses the Distance Determination Algorithm. More...
 
class  Stage
 A Stage is a data structure that wraps a function, and taking in parameter Input and returning Output. More...
 
struct  Vec2
 A Vec2 is an immutable object that represents a 2D Vector. More...
 
class  Vec3
 A Vec3 is a mutable object that represents a 3D Vector. More...
 
class  VectorGenerationAlgorithm
 The VectorGenerationAlgorithm class houses the Vector Assembly Algorithm. More...
 

Typedefs

typedef __float128 PreciseDecimal
 Alias for very precise floating point numbers.
 
typedef std::vector< Vec2Points
 The output for Edge Detection Algorithms (edge.hpp/cpp).
 
typedef Vec3 PositionVector
 The output for Vector Assembly Algorithms (vectorize.hpp).
 
typedef std::vector< EdgeEdges
 A collection of Edges.
 
typedef std::vector< ComponentComponents
 A collection of Image Pixels.
 
typedef std::vector< LocationRecordLocationRecords
 A collection of Location Records.
 
typedef struct OrbitParams OrbitParams
 The output for Orbit Trajectory Calculation Algorithms.
 
typedef std::pair< std::function< Vec3(int)>, std::function< Vec3(int)> > KinematicPrediction
 The output for Kinematic Profile Completion.
 
typedef Pipeline< std::pair< EulerAngles, EulerAngles >, QuaternionCalibrationPipeline
 Pipeline for Calibration.
 
typedef Pipeline< Image, PositionVectorDistancePipeline
 Pipeline for Distance Determination.
 
typedef Pipeline< LocationRecords, LocationRecordsOrbitPipeline
 Pipeline for Orbital Determination.
 

Functions

int main (int argc, char **argv)
 This is where the program starts.
 
CalibrationOptions ParseCalibrationOptions (int argc, char **argv)
 Parses the calibration options from the command line to run the calibration algorithm.
 
DistanceOptions ParseDistanceOptions (int argc, char **argv)
 Parses the distance options from the command line to run the distance determination algorithm.
 
OrbitOptions ParseOrbitOptions (int argc, char **argv)
 Parses the orbit options from the command line to run the orbit determination algorithm.
 
Quaternion SphericalToQuaternion (decimal ra, decimal dec, decimal roll)
 Converts Euler Angles into a quaternion.
 
Vec3 SphericalToSpatial (const decimal ra, const decimal de)
 Converts spherical direction to a unit vector on the unit sphere.
 
void SpatialToSpherical (const Vec3 &vec, decimal &ra, decimal &de)
 Converts a unit vector on the unit sphere to a spherical direction.
 
decimal RadToArcSec (decimal rad)
 Calculates the approximate value for the inverse secant of an angle.
 
decimal ArcSecToRad (decimal arcSec)
 Calculates an angle from an inverse secant value.
 
Vec2 midpoint (const Vec2 &vec1, const Vec2 &vec2)
 Finds the midpoint between two different vectors.
 
Vec3 midpoint (const Vec3 &vec1, const Vec3 &vec2)
 Finds the midpoint between two different vectors.
 
Vec3 midpoint (const Vec3 &vec1, const Vec3 &vec2, const Vec3 &vec3)
 Finds the midpoint between three different vectors.
 
decimal Angle (const Vec3 &vec1, const Vec3 &vec2)
 Determines the angle between two different vectors.
 
decimal AngleUnit (const Vec3 &vec1, const Vec3 &vec2)
 Determines the angle between two different vectors.
 
decimal Distance (const Vec2 &v1, const Vec2 &v2)
 Determines the Distance between two vectors.
 
decimal Distance (const Vec3 &v1, const Vec3 &v2)
 Determines the Distance between two vectors.
 
Mat3 QuaternionToDCM (const Quaternion &quat)
 Creates a Direction Cosine Matrix (DCM) off of a Quaternion.
 
Quaternion DCMToQuaternion (const Mat3 &dcm)
 Creates a Quaternion based on a Direction Cosine Matrix (rotation matrix)
 
int64_t SerializeLengthVec3 ()
 Computes the size, in bytes, that a Vec3 object will take up.
 
void SerializeVec3 (const Vec3 &vec, unsigned char *buffer)
 Serializes a Vec3 into a buffer.
 
Vec3 DeserializeVec3 (const unsigned char *buffer)
 Deserializes a Vec3 from a buffer.
 
Quaternion SphericalToQuaternion (EulerAngles angles)
 Converts Euler Angles into a quaternion.
 
constexpr decimal RadToDeg (decimal rad)
 Converts an angle in radians to degrees.
 
constexpr decimal DegToRad (decimal deg)
 Converts an angle in degrees to radians.
 
decimal FovToFocalLength (decimal xFov, decimal xResolution)
 Provides the focal length of a camera for given parameters.
 
decimal FocalLengthToFov (decimal focalLength, decimal xResolution, decimal pixelSize)
 Provides the FOV of a camera for given parameters.
 
DateTime getUTCTime ()
 Obtains the current UTC time in unix/epoch seconds.
 
DateTime getUT1Time ()
 Obtains the current UT1 time in unix/epoch seconds.
 
decimal getJulianDateTime (DateTime &time)
 Obtains the current Julian date in decimal format.
 
decimal getCurrentJulianDateTime ()
 Obtains the current Julian date in decimal format.
 
decimal getJulianDateTime (std::time_t epochs)
 Obtains the Julian date from the given epochs in seconds.
 
decimal getGreenwichMeanSiderealTime (DateTime &time)
 Obtains the Greenwich Mean Sidereal Time in decimal format.
 
decimal getCurrentGreenwichMeanSiderealTime ()
 Obtians the current Greenwich Mean Sidereal Time in decimal format.
 
decimal getGreenwichMeanSiderealTime (std::time_t epochs)
 Obtains the Greenwich Mean Sidereal Time in decimal format from the given epochs.
 
uint16_t htons (uint16_t v)
 Converts a 16-bit integer from host byte order to network byte order.
 
uint16_t ntohs (uint16_t v)
 Converts a 16-bit integer from network byte order to host byte order.
 
uint32_t htonl (uint32_t v)
 Converts a 32-bit integer from host byte order to network byte order.
 
uint32_t ntohl (uint32_t v)
 Converts a 32-bit integer from network byte order to host byte order.
 
uint64_t htonl (uint64_t v)
 Converts a 64-bit integer from host byte order to network byte order.
 
uint64_t ntohl (uint64_t v)
 Converts a 64-bit integer from network byte order to host byte order.
 
float htonf (float v)
 Converts a float from network byte order to host byte order.
 
float ntohf (float v)
 Converts a float from network byte order to host byte order.
 
double ntohd (double v)
 Converts a double from network byte order to host byte order.
 
double htond (double v)
 Converts a double from host byte order to network byte order.
 
decimal htondec (decimal v)
 Converts a decimal from host byte order to network byte order.
 
decimal ntohdec (decimal v)
 Converts a decimal from network byte order to host byte order.
 
uint32_t calculateCRC32 (const void *data, size_t length)
 Calculates the CRC32 checksum for a given data buffer.
 
void hton (DataFileHeader &header)
 Converts a DataFileHeader from host to network byte order.
 
void ntoh (DataFileHeader &header)
 Converts a DataFileHeader from network to host byte order.
 
void write (std::ostream &stream, const decimal &value)
 Writes a decimal value to the given output stream in network byte order.
 
void read (std::istream &stream, decimal &value)
 Reads a decimal value from the given input stream.
 
void write (std::ostream &stream, const uint64_t &value)
 Writes a 64-bit unsigned integer to the given output stream in network byte order.
 
void read (std::istream &stream, uint64_t &value)
 Reads a 64-bit unsigned integer from the given input stream.
 
void write (std::ostream &stream, const uint32_t &value)
 Writes a 32-bit unsigned integer to the given output stream in network byte order.
 
void read (std::istream &stream, uint32_t &value)
 Reads a 32-bit unsigned integer from the given input stream in network byte order.
 
void write (std::ostream &stream, const Quaternion &quat)
 Serializes an Quaternion to the given output stream.
 
void read (std::istream &stream, Quaternion &quat)
 Reads Quaternion data from an input stream.
 
void write (std::ostream &stream, const Vec3 &v)
 Serializes a Vec3 object to the given output stream.
 
void read (std::istream &stream, Vec3 &v)
 Reads a Vec3 object from the given input stream.
 
void write (std::ostream &stream, const LocationRecord &record)
 Serializes a LocationRecord object to the given output stream.
 
void read (std::istream &stream, LocationRecord &record)
 Reads data from the input stream into a LocationRecord object.
 
void serializeDataFile (const DataFile &data, std::ostream &stream)
 Serializes a DataFile object to an output stream.
 
DataFile deserializeDataFile (std::istream &stream)
 Deserializes a DataFile object from an input stream.
 
DataFile deserializeDataFile (std::istream &stream, const std::string &path)
 Deserializes a DataFile object from an input stream.
 
bool isValidMagicNumber (const char magic[4])
 Validates the magic number in the header.
 
DataFileHeader readHeader (std::istream &stream)
 Reads only the header of a DataFile from an input stream.
 
bool LabelPresent (int label, int *adjacentLabels, int size)
 Checks if a label is present in the list of adjacent labels.
 
void UpdateComponent (Component &component, uint64_t index, Vec2 &pixel)
 Updates the component with the given pixel.
 
int NWayEquivalenceAdd (const Image &image, uint64_t index, int &L, int adjacentLabels[4], int size, std::unordered_map< int, Component > &components, std::unordered_map< int, int > &equivalencies)
 Adds a pixel to some component, creating a new component if necessary.
 
Components ConnectedComponentsAlgorithm (const Image &image, std::function< bool(uint64_t, const Image &)> Criteria)
 Computes the groups of components within the image.
 
EarthSphericalVec3 GetEarthCoordinates (Vec3 &celestialVector, decimal gmst)
 Obtains a celestial vector within Earth's Rotating Frame, in longitude/lattitude/altitude.
 
unsigned char strtouc (const std::string &str)
 Converts a string to an unsigned char.
 
size_t strtosize (const std::string &str)
 
decimal strtodecimal (const std::string &str)
 Converts a string to a decimal.
 
EulerAngles strtoea (const std::string &str)
 Converts a string to euler angles.
 
bool strtobool (const std::string &str)
 Converts the string to a bool.
 
Image strtoimage (const std::string &str)
 Converts a string to an image.
 
DataFile strtodf (const std::string &str)
 
LocationRecords strtolr (const std::string &str)
 Converts a string to a vector of location records.
 
std::unique_ptr< CalibrationPipelineExecutorCreateCalibrationPipelineExecutor (CalibrationOptions &&options)
 Creates a CalibrationPipelineExecutor.
 
std::unique_ptr< DistancePipelineExecutorCreateDistancePipelineExecutor (DistanceOptions &&options)
 Creates a DistancePipelineExecutor.
 
std::unique_ptr< CalibrationAlgorithmProvideCalibrationAlgorithm (CalibrationOptions &&options)
 Provides a CalibrationAlgorithm.
 
std::unique_ptr< EdgeDetectionAlgorithmProvideEdgeDetectionAlgorithm (DistanceOptions &&options)
 Provides an EdgeDetectionAlgorithm.
 
std::unique_ptr< DistanceDeterminationAlgorithmProvideDistanceDeterminationAlgorithm (DistanceOptions &&options)
 Provides a DistanceDeterminationAlgorithm.
 
std::unique_ptr< VectorGenerationAlgorithmProvideVectorGenerationAlgorithm (DistanceOptions &&options)
 Provides a VectorGenerationAlgorithm.
 

Variables

const char kNoDefaultArgument = 0
 For macro processing.
 
const Mat3 kIdentityMat3
 3x3 identity matrix
 

Typedef Documentation

◆ CalibrationPipeline

◆ Components

typedef std::vector<Component> found::Components

A collection of Image Pixels.

◆ DistancePipeline

Pipeline for Distance Determination.

◆ Edges

typedef std::vector<Edge> found::Edges

A collection of Edges.

◆ KinematicPrediction

typedef std::pair<std::function<Vec3(int)>,std::function<Vec3(int)> > found::KinematicPrediction

The output for Kinematic Profile Completion.

Currently set to two functions that will tell you the position and velocity of the satellite at any given time

◆ LocationRecords

typedef std::vector<LocationRecord> found::LocationRecords

A collection of Location Records.

◆ OrbitParams

The output for Orbit Trajectory Calculation Algorithms.

Currently set to a struct that holds the orbit equations.

◆ OrbitPipeline

◆ Points

typedef std::vector<Vec2> found::Points

The output for Edge Detection Algorithms (edge.hpp/cpp).

Currently set to a vector of 2D points on the image, according to image coordinate systems

◆ PositionVector

The output for Vector Assembly Algorithms (vectorize.hpp).

Currently set to a 3D Vector that represents the satellite's position relative to Earth's coordinate system.

◆ PreciseDecimal

typedef __float128 found::PreciseDecimal

Alias for very precise floating point numbers.

Function Documentation

◆ Angle()

decimal found::Angle ( const Vec3 vec1,
const Vec3 vec2 
)

Determines the angle between two different vectors.

Parameters
vec1The first vector
vec2The second vector
Returns
The angle, in radians, between vec1 and vec2

◆ AngleUnit()

decimal found::AngleUnit ( const Vec3 vec1,
const Vec3 vec2 
)

Determines the angle between two different vectors.

Parameters
vec1The first vector
vec2The second vector
Returns
The angle, in radians, between vec1 and vec2
Precondition
The magnitude of vec1 and vec2 are 1
Warning
vec1 and vec2 must have a magnitude of 1

◆ ArcSecToRad()

decimal found::ArcSecToRad ( decimal  arcSec)

Calculates an angle from an inverse secant value.

Parameters
arcSecThe arcsecant value
Returns
A possible angle value, in radians, corresponding to the arcsecant value arcSec

◆ calculateCRC32()

uint32_t found::calculateCRC32 ( const void *  data,
size_t  length 
)

Calculates the CRC32 checksum for a given data buffer.

Parameters
dataPointer to the data buffer.
lengthThe size of the data buffer in bytes.
Returns
The calculated CRC32 checksum.

◆ ConnectedComponentsAlgorithm()

Components found::ConnectedComponentsAlgorithm ( const Image image,
std::function< bool(uint64_t, const Image &)>  Criteria 
)

Computes the groups of components within the image.

Parameters
imageThe image that defines the possible pixels
CriteriaA function that accepts a pixel index and the image and returns true iff the pixel is part of the component
Returns
Components The components that are part of the image
Note
This function iterates through each pixel in the image, but treats the image as 2D, not 3D. You must program Criteria correctly to handle cases where there are multiple channels (i.e. This algorithm doesn't know how many channels are involved).

◆ CreateCalibrationPipelineExecutor()

std::unique_ptr< CalibrationPipelineExecutor > found::CreateCalibrationPipelineExecutor ( CalibrationOptions &&  options)
inline

Creates a CalibrationPipelineExecutor.

Parameters
optionsThe options to create the pipeline executor from
Returns
A pointer to a CalibrationPipelineExecutor

◆ CreateDistancePipelineExecutor()

std::unique_ptr< DistancePipelineExecutor > found::CreateDistancePipelineExecutor ( DistanceOptions &&  options)
inline

Creates a DistancePipelineExecutor.

Parameters
optionsThe options to create the pipeline executor from
Returns
A pointer to a DistancePipelineExecutor

◆ DCMToQuaternion()

Quaternion found::DCMToQuaternion ( const Mat3 dcm)

Creates a Quaternion based on a Direction Cosine Matrix (rotation matrix)

Parameters
dcmThe matrix holding the direction cosines
Returns
A Quaternion that expresses the rotation defined in dcm

◆ DegToRad()

constexpr decimal found::DegToRad ( decimal  deg)
constexpr

Converts an angle in degrees to radians.

Parameters
degThe degrees of the angle
Returns
The radians of the angle

◆ deserializeDataFile() [1/2]

DataFile found::deserializeDataFile ( std::istream &  stream)

Deserializes a DataFile object from an input stream.

Parameters
streamThe input stream to read the serialized data from.
Returns
The deserialized DataFile object.

◆ deserializeDataFile() [2/2]

DataFile found::deserializeDataFile ( std::istream &  stream,
const std::string &  path 
)

Deserializes a DataFile object from an input stream.

Parameters
streamThe input stream to read the serialized data from.
pathThe path to associate the resulting struct with
Returns
The deserialized DataFile object, with the given path.

◆ DeserializeVec3()

Vec3 found::DeserializeVec3 ( const unsigned char *  buffer)

Deserializes a Vec3 from a buffer.

Parameters
bufferThe buffer to obtain the vector from. This parameter should point to the location of the Vec3 within the buffer.
Returns
A Vec3 representing the Vec3 stored in the buffer
Precondition
buffer points to a valid location storing a Vec3
Warning
Returns nonsense if buffer does not point to a valid location that stores a Vec3

◆ Distance() [1/2]

decimal found::Distance ( const Vec2 v1,
const Vec2 v2 
)

Determines the Distance between two vectors.

Parameters
v1The first vector
v2The second vector
Returns
The distance between v1 and v2

◆ Distance() [2/2]

decimal found::Distance ( const Vec3 v1,
const Vec3 v2 
)

Determines the Distance between two vectors.

Parameters
v1The first vector
v2The second vector
Returns
The distance between v1 and v2

◆ FocalLengthToFov()

decimal found::FocalLengthToFov ( decimal  focalLength,
decimal  xResolution,
decimal  pixelSize 
)

Provides the FOV of a camera for given parameters.

Parameters
focalLengthThe focal length
xResolutionThe horizontal resolution
pixelSizeThe size of a pixel in a Camera
Returns
The FOV of a camera with a given focalLength, xResolution, and pixelSize

◆ FovToFocalLength()

decimal found::FovToFocalLength ( decimal  xFov,
decimal  xResolution 
)

Provides the focal length of a camera for given parameters.

Parameters
xFovThe horizontal field of view
xResolutionThe horizontal resolution
Returns
The focal length of a camera with a given xFov and xResolution

◆ getCurrentGreenwichMeanSiderealTime()

decimal found::getCurrentGreenwichMeanSiderealTime ( )

Obtians the current Greenwich Mean Sidereal Time in decimal format.

Returns
The current Greenwich Mean Sidereal Time in degrees

◆ getCurrentJulianDateTime()

decimal found::getCurrentJulianDateTime ( )

Obtains the current Julian date in decimal format.

Returns
The current Julian date

◆ GetEarthCoordinates()

EarthSphericalVec3 found::GetEarthCoordinates ( Vec3 celestialVector,
decimal  gmst 
)

Obtains a celestial vector within Earth's Rotating Frame, in longitude/lattitude/altitude.

Parameters
celestialVectorThe celestial vector to convert
gmstThe current GMST value, in degrees
Returns
An EarthSphericalVec3 describing celestialVector within Earth's Rotating Frame at time GMST
Precondition
celestialVector must be in the frame of the celestial coordinate system NOT the camera coordinate system

◆ getGreenwichMeanSiderealTime() [1/2]

decimal found::getGreenwichMeanSiderealTime ( DateTime time)

Obtains the Greenwich Mean Sidereal Time in decimal format.

Parameters
timeThe DateTime to convert
Returns
The Greenwich Mean Sidereal Time corresponding to time, in degrees
Precondition
The time must be in UT1

◆ getGreenwichMeanSiderealTime() [2/2]

decimal found::getGreenwichMeanSiderealTime ( std::time_t  epochs)

Obtains the Greenwich Mean Sidereal Time in decimal format from the given epochs.

Parameters
epochsThe epochs in seconds
Returns
The Greenwich Mean Sidereal Time corresponding to the given epochs in degrees

◆ getJulianDateTime() [1/2]

decimal found::getJulianDateTime ( DateTime time)

Obtains the current Julian date in decimal format.

Parameters
timeThe DateTime to convert
Returns
The Julian date corresponding to time

◆ getJulianDateTime() [2/2]

decimal found::getJulianDateTime ( std::time_t  epochs)

Obtains the Julian date from the given epochs in seconds.

Parameters
epochsThe epochs in seconds
Returns
The Julian date corresponding to the given epochs

◆ getUT1Time()

DateTime found::getUT1Time ( )

Obtains the current UT1 time in unix/epoch seconds.

Returns
The current UT1 time

◆ getUTCTime()

DateTime found::getUTCTime ( )

Obtains the current UTC time in unix/epoch seconds.

Returns
The current UTC Time

◆ hton()

void found::hton ( DataFileHeader header)

Converts a DataFileHeader from host to network byte order.

Parameters
headerThe header to convert.
Postcondition
header's fields are in network byte order.

◆ htond()

double found::htond ( double  v)
inline

Converts a double from host byte order to network byte order.

Parameters
vThe double value to convert.
Returns
The converted double value in network byte order.

◆ htondec()

decimal found::htondec ( decimal  v)
inline

Converts a decimal from host byte order to network byte order.

Parameters
vThe decimal value to convert.
Returns
The converted decimal value in network byte order.

◆ htonf()

float found::htonf ( float  v)
inline

Converts a float from network byte order to host byte order.

Parameters
vThe float value to convert.
Returns
The converted float value in host byte order.

◆ htonl() [1/2]

uint32_t found::htonl ( uint32_t  v)
inline

Converts a 32-bit integer from host byte order to network byte order.

Parameters
vThe integer to convert
Returns
The integer in network byte order.

◆ htonl() [2/2]

uint64_t found::htonl ( uint64_t  v)
inline

Converts a 64-bit integer from host byte order to network byte order.

Parameters
vThe integer to convert
Returns
The integer in network byte order.

◆ htons()

uint16_t found::htons ( uint16_t  v)
inline

Converts a 16-bit integer from host byte order to network byte order.

Parameters
vThe integer to convert
Returns
The integer in network byte order.

◆ isValidMagicNumber()

bool found::isValidMagicNumber ( const char  magic[4])

Validates the magic number in the header.

Parameters
magicThe magic number to validate
Returns
true iff magic == "FOUN"

◆ LabelPresent()

bool found::LabelPresent ( int  label,
int *  adjacentLabels,
int  size 
)
inline

Checks if a label is present in the list of adjacent labels.

Parameters
labelThe label to check
adjacentLabelsThe list of adjacent labels
sizeThe size of the list
Returns
true iff label is in adjacentLabels

◆ main()

int found::main ( int  argc,
char **  argv 
)

This is where the program starts.

Parameters
argcThe number of arguments passed into the command line
argvThe arguments passed into the command line
Returns
An integer indicating success (0) iff the program executes successfully
Note
The method itself uses command line arguments to generate an Options object that represents all the algorithms we want to run and their parameters

◆ midpoint() [1/3]

Vec2 found::midpoint ( const Vec2 vec1,
const Vec2 vec2 
)

Finds the midpoint between two different vectors.

Parameters
vec1The first vector
vec2The second vector
Returns
The midpoint vector

◆ midpoint() [2/3]

Vec3 found::midpoint ( const Vec3 vec1,
const Vec3 vec2 
)

Finds the midpoint between two different vectors.

Parameters
vec1The first vector
vec2The second vector
Returns
The midpoint vector

◆ midpoint() [3/3]

Vec3 found::midpoint ( const Vec3 vec1,
const Vec3 vec2,
const Vec3 vec3 
)

Finds the midpoint between three different vectors.

Parameters
vec1The first vector
vec2The second vector
vec3The third vector
Returns
The midpoint vector

◆ ntoh()

void found::ntoh ( DataFileHeader header)

Converts a DataFileHeader from network to host byte order.

Parameters
headerThe header to convert.
Postcondition
header's fields are in host byte order.

◆ ntohd()

double found::ntohd ( double  v)
inline

Converts a double from network byte order to host byte order.

Parameters
vThe double value to convert.
Returns
The converted double value in host byte order.

◆ ntohdec()

decimal found::ntohdec ( decimal  v)
inline

Converts a decimal from network byte order to host byte order.

Parameters
vThe decimal value to convert.
Returns
The converted decimal value in host byte order.

◆ ntohf()

float found::ntohf ( float  v)
inline

Converts a float from network byte order to host byte order.

Parameters
vThe float value to convert.
Returns
The converted float value in host byte order.

◆ ntohl() [1/2]

uint32_t found::ntohl ( uint32_t  v)
inline

Converts a 32-bit integer from network byte order to host byte order.

Parameters
vThe integer to convert
Returns
The integer in host byte order.

◆ ntohl() [2/2]

uint64_t found::ntohl ( uint64_t  v)
inline

Converts a 64-bit integer from network byte order to host byte order.

Parameters
vThe integer to convert
Returns
The integer in host byte order.

◆ ntohs()

uint16_t found::ntohs ( uint16_t  v)
inline

Converts a 16-bit integer from network byte order to host byte order.

Parameters
vThe integer to convert
Returns
The integer in host byte order.

◆ NWayEquivalenceAdd()

int found::NWayEquivalenceAdd ( const Image image,
uint64_t  index,
int &  L,
int  adjacentLabels[4],
int  size,
std::unordered_map< int, Component > &  components,
std::unordered_map< int, int > &  equivalencies 
)
inline

Adds a pixel to some component, creating a new component if necessary.

Parameters
imageThe image to which the pixel belongs
indexThe index of the pixel
LThe current label
adjacentLabelsThe labels of the adjacent components
sizeThe number of adjacent labels
componentsThe components that are part of the image
equivalenciesThe labels that are equivalent to each other
Returns
The label of the component point that was added

Updates components with the new pixel as appropriate

◆ ParseCalibrationOptions()

CalibrationOptions found::ParseCalibrationOptions ( int  argc,
char **  argv 
)

Parses the calibration options from the command line to run the calibration algorithm.

Parameters
argcThe number of command-line arguments
argvThe command line arguments
Returns
CalibrationOptions The options for the calibration algorithm as extracted on the command line

◆ ParseDistanceOptions()

DistanceOptions found::ParseDistanceOptions ( int  argc,
char **  argv 
)

Parses the distance options from the command line to run the distance determination algorithm.

Parameters
argcThe number of command-line arguments
argvThe command line arguments
Returns
DistanceOptions The options for the distance determination algorithm as extracted on the command line

◆ ParseOrbitOptions()

OrbitOptions found::ParseOrbitOptions ( int  argc,
char **  argv 
)

Parses the orbit options from the command line to run the orbit determination algorithm.

Parameters
argcThe number of command-line arguments
argvThe command line arguments
Returns
OrbitOptions The options for the orbit determination algorithm as extracted from the command line

◆ ProvideCalibrationAlgorithm()

std::unique_ptr< CalibrationAlgorithm > found::ProvideCalibrationAlgorithm ( CalibrationOptions &&  options)

Provides a CalibrationAlgorithm.

Parameters
optionsThe options to derive the calibration algorithm from
Returns
A pointer to the CalibrationAlgorithm

◆ ProvideDistanceDeterminationAlgorithm()

std::unique_ptr< DistanceDeterminationAlgorithm > found::ProvideDistanceDeterminationAlgorithm ( DistanceOptions &&  options)

Provides a DistanceDeterminationAlgorithm.

Parameters
optionsThe options to derive the distance determination algorithm from
Returns
std::unique_ptr<DistanceDeterminationAlgorithm> The distance determination algorithm

◆ ProvideEdgeDetectionAlgorithm()

std::unique_ptr< EdgeDetectionAlgorithm > found::ProvideEdgeDetectionAlgorithm ( DistanceOptions &&  options)

Provides an EdgeDetectionAlgorithm.

Parameters
optionsThe options to derive the edge detection algorithm from
Returns
std::unique_ptr<EdgeDetectionAlgorithm> The edge detection algorithm

◆ ProvideVectorGenerationAlgorithm()

std::unique_ptr< VectorGenerationAlgorithm > found::ProvideVectorGenerationAlgorithm ( DistanceOptions &&  options)

Provides a VectorGenerationAlgorithm.

Parameters
optionsThe options to derive the vector generation algorithm from
Returns
std::unique_ptr<VectorGenerationAlgorithm> The vector generation algorithm

◆ QuaternionToDCM()

Mat3 found::QuaternionToDCM ( const Quaternion quat)

Creates a Direction Cosine Matrix (DCM) off of a Quaternion.

Parameters
quatThe quaternion to base the DCM off of
Returns
A Matrix holding the direction cosines of a particular attitude (orientation)
Note
A DCM is also a rotation matrix. If B is a DCM, multiplying B by Vector v will result in vector u where u is v rotated to the angles that the direction cosines hold.

◆ RadToArcSec()

decimal found::RadToArcSec ( decimal  rad)

Calculates the approximate value for the inverse secant of an angle.

Parameters
radThe angle, in radians
Returns
The arcsecant of the angle
Precondition
rad is in radians
Warning
rad must be in radians

◆ RadToDeg()

constexpr decimal found::RadToDeg ( decimal  rad)
constexpr

Converts an angle in radians to degrees.

Parameters
radThe rad of the angle
Returns
The degrees of the angle

◆ read() [1/6]

void found::read ( std::istream &  stream,
decimal value 
)
inline

Reads a decimal value from the given input stream.

Parameters
streamThe stream to read from
valueThe value to write into
Postcondition
value is now the decimal value that is at the position where stream is, in host byte order

◆ read() [2/6]

void found::read ( std::istream &  stream,
LocationRecord record 
)
inline

Reads data from the input stream into a LocationRecord object.

Parameters
streamThe stream to read from
recordThe LocationRecord to write into
Postcondition
record has the values that stream held

◆ read() [3/6]

void found::read ( std::istream &  stream,
Quaternion quat 
)
inline

Reads Quaternion data from an input stream.

Parameters
streamThe stream to read from
quatThe angles to write into
Postcondition
quat has the values that stream held

◆ read() [4/6]

void found::read ( std::istream &  stream,
uint32_t &  value 
)
inline

Reads a 32-bit unsigned integer from the given input stream in network byte order.

Parameters
streamThe stream to read from
valueThe value to write into
Postcondition
value is now the integer value that is at the position where stream is, in host byte order

◆ read() [5/6]

void found::read ( std::istream &  stream,
uint64_t &  value 
)
inline

Reads a 64-bit unsigned integer from the given input stream.

Parameters
streamThe stream to read from
valueThe value to write into
Postcondition
value is now the integer value that is at the position where stream is, in host byte order

◆ read() [6/6]

void found::read ( std::istream &  stream,
Vec3 v 
)
inline

Reads a Vec3 object from the given input stream.

Parameters
streamThe stream to read from
vThe Vec3 to write into
Postcondition
v has the values that stream held

◆ readHeader()

DataFileHeader found::readHeader ( std::istream &  stream)

Reads only the header of a DataFile from an input stream.

Parameters
streamThe input stream to read the header from.
Returns
The DataFileHeader object containing the header information.

◆ serializeDataFile()

void found::serializeDataFile ( const DataFile data,
std::ostream &  stream 
)

Serializes a DataFile object to an output stream.

Parameters
dataThe DataFile object to serialize.
streamThe output stream to write the serialized data to.
Precondition
The number of positions in the header must match the number of positions in the entry.

◆ SerializeLengthVec3()

int64_t found::SerializeLengthVec3 ( )

Computes the size, in bytes, that a Vec3 object will take up.

Returns
The number of bytes that a Vec3 occupies

◆ SerializeVec3()

void found::SerializeVec3 ( const Vec3 vec,
unsigned char *  buffer 
)

Serializes a Vec3 into a buffer.

Parameters
vecThe vector to serialize.
bufferThe buffer to insert the vector into
Postcondition
The parameter buffer will hold vec after the operation of this function.
Note
A buffer is a very long character array that holds information that the user defines. Serialization of data means inputting certain data into a buffer.

◆ SpatialToSpherical()

void found::SpatialToSpherical ( const Vec3 vec,
decimal ra,
decimal de 
)

Converts a unit vector on the unit sphere to a spherical direction.

Parameters
vecThe vector to convert from
raThe right ascension that will represent the right ascension of vec
deThe declination that will represent the declination of vec
Postcondition
This function's output are the parameters ra and de, and those parameters are modified after this function runs.

◆ SphericalToQuaternion() [1/2]

Quaternion found::SphericalToQuaternion ( decimal  ra,
decimal  dec,
decimal  roll 
)

Converts Euler Angles into a quaternion.

Parameters
raThe right ascension of the Euler Angles
decThe declination of the Euler Angles
rollThe roll of the Euler Angles
Returns
A Quaternion representing this collection of Euler Angles
Note
Returned Quaternion will reorient the coordinate axes so that the x-axis points at the given right ascension and declination, then roll the coordinate axes counterclockwise (i.e., the stars will appear to rotate clockwise). This is an "improper" z-y'-x' Euler rotation.
Rotating a vector with this quaternion is equivalent to a forwards rotation (rotation into the absolute frame)

◆ SphericalToQuaternion() [2/2]

Quaternion found::SphericalToQuaternion ( EulerAngles  angles)
inline

Converts Euler Angles into a quaternion.

Parameters
anglesThe euler angles to convert
Returns
A Quaternion representing this collection of Euler Angles
Note
Returned Quaternion will reorient the coordinate axes so that the x-axis points at the given right ascension and declination, then roll the coordinate axes counterclockwise (i.e., the stars will appear to rotate clockwise). This is an "improper" z-y'-x' Euler rotation.

◆ SphericalToSpatial()

Vec3 found::SphericalToSpatial ( const decimal  ra,
const decimal  de 
)

Converts spherical direction to a unit vector on the unit sphere.

Parameters
raThe right ascension of the direction in question
deThe declination of the direction in question
Returns
A 3D unit vector that represents the vector on the unit sphere corresponding to this direction

◆ strtobool()

bool found::strtobool ( const std::string &  str)
inline

Converts the string to a bool.

Parameters
strThe string to convert
Returns
true iff the string represents a true value

◆ strtodecimal()

decimal found::strtodecimal ( const std::string &  str)
inline

Converts a string to a decimal.

Parameters
strThe string to convert
Returns
The decimal numeber this string represents
Precondition
The str must actually represent a decimal

◆ strtodf()

DataFile found::strtodf ( const std::string &  str)
inline

◆ strtoea()

EulerAngles found::strtoea ( const std::string &  str)
inline

Converts a string to euler angles.

Parameters
strThe string to convert
Returns
An EulerAngle corresponding to the string, if the str is valid
Precondition
The string must have 3 decimal values seperated by commas or spaces

◆ strtoimage()

Image found::strtoimage ( const std::string &  str)
inline

Converts a string to an image.

Parameters
strThe string to convert
Returns
The image that the string represents
Note
This function uses stb_image.h to load the image
Exceptions
std::runtime_errorif the image cannot be loaded

◆ strtolr()

LocationRecords found::strtolr ( const std::string &  str)
inline

Converts a string to a vector of location records.

Parameters
strThe string to convert
Returns
The vector of location records that the string represents
Precondition
str must refer to a file, either the Data File, or a space delinated file with the following format on each line: Timestamp(int) PositionX(decimal) PositionY(decimal) PositionZ(decimal)

◆ strtosize()

size_t found::strtosize ( const std::string &  str)
inline

◆ strtouc()

unsigned char found::strtouc ( const std::string &  str)
inline

Converts a string to an unsigned char.

Parameters
strThe string to convert
Returns
The unsigned char the string represents
Precondition
str represents a number between 0 and 255

◆ UpdateComponent()

void found::UpdateComponent ( Component component,
uint64_t  index,
Vec2 pixel 
)
inline

Updates the component with the given pixel.

Parameters
componentThe component to update
indexThe index to add
pixelThe pixel to add
Precondition
Must be called in order of increasing index

◆ write() [1/6]

void found::write ( std::ostream &  stream,
const decimal value 
)
inline

Writes a decimal value to the given output stream in network byte order.

Parameters
streamThe stream to write into
valueThe value to read from
Postcondition
stream has value written into it, in network byte order

◆ write() [2/6]

void found::write ( std::ostream &  stream,
const LocationRecord record 
)
inline

Serializes a LocationRecord object to the given output stream.

Parameters
streamThe stream to read from
recordThe record to write into
Postcondition
record has the values that stream held

◆ write() [3/6]

void found::write ( std::ostream &  stream,
const Quaternion quat 
)
inline

Serializes an Quaternion to the given output stream.

Parameters
streamThe stream to write into
quatThe angles to read from
Postcondition
stream has all fields of quat written into it, each in network byte order.

◆ write() [4/6]

void found::write ( std::ostream &  stream,
const uint32_t &  value 
)
inline

Writes a 32-bit unsigned integer to the given output stream in network byte order.

Parameters
streamThe stream to write into
valueThe value to read from
Postcondition
stream has value written into it, in network byte order

◆ write() [5/6]

void found::write ( std::ostream &  stream,
const uint64_t &  value 
)
inline

Writes a 64-bit unsigned integer to the given output stream in network byte order.

Parameters
streamThe stream to write into
valueThe value to read from
Postcondition
stream has value written into it, in network byte order

◆ write() [6/6]

void found::write ( std::ostream &  stream,
const Vec3 v 
)
inline

Serializes a Vec3 object to the given output stream.

Parameters
streamThe stream to write into
vThe Vec3 to read from
Postcondition
stream has all fields of v written into it, each in network byte order.

Variable Documentation

◆ kIdentityMat3

const Mat3 found::kIdentityMat3
Initial value:
= {1,0,0,
0,1,0,
0,0,1}

3x3 identity matrix

◆ kNoDefaultArgument

const char found::kNoDefaultArgument = 0

For macro processing.