ModelSpace
Documentation for ModelSpace models and classes.
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Pages
cfspp Namespace Reference

Classes

class  DeadReckon
 GNC App for performing the propagation step of an EKF when an IMU is available to report the angular velocity and acceleration (without gravity). This app is an implementation if a strapdown IMU based dead-reckoning integration of an objects position, velocity, and attitude relative to some inertial frame (this frame can be pseudoinertial, use your best judgement). This form of propagation step is best used if there are significant external/internal forces other than gravity acting on the system, also forces that cannot be modeled easily as functions of the state vector. More...
 
class  GPSUpdate
 GNC App for performing the GPS measurement update step of an EKF when a GPS receiver is available to report the vehicle position in a known reference frame (e.g., ECEF, ECI, or NED). This app implements the EKF measurement correction step by comparing the measured GPS position (after necessary frame and lever-arm transformations) to the predicted position from the EKF state. More...
 
class  MagUpdate
 GNC App for performing the magnetometer measurement update step of an EKF when a 3-axis magnetometer is available to report the local magnetic field vector. This app implements the EKF measurement correction step by comparing the measured magnetic field in the magnetometer frame to the expected magnetic field derived from an internal model (e.g., WMM, IGRF, lookup table) and the current state estimate. More...
 
class  LedBlinker
 LED Blinker example app. More...
 
class  PdAttitudeControl
 Simple PD attitude controller. More...
 
class  TwoAxisPointingGuidance
 Two-axis constrained pointing guidance method guidance. More...
 
struct  PlanetDefaults
 Contain all default values defined for a planet. More...
 
class  App
 Base app class for derived implementation. More...
 
struct  RegisteredCommandInfo
 Struct to store info on registered commands. More...
 
class  CommandManager
 This class routes commands from the HAL to associated Apps. More...
 
class  FlightExecutive
 Executive derivation specifically to run flight systems. More...
 
class  OS
 Holds all os-specific interfaces. More...
 
struct  GpioConfig_t
 Struct type definition for GPIO configuration interface. More...
 
struct  SpiConfig_t
 Struct type definition for SPI configuration interface. More...
 
struct  UartConfig_t
 Struct type definition for UART configuration interface. More...
 
struct  I2cConfig_t
 Struct type definition for I2C configuration interface. More...
 
struct  PwmConfig_t
 Struct type definition for I2C configuration interface. More...
 
class  Platform
 Holds all platform-specific interfaces. More...
 
class  Scheduler
 Base class implementation of the scheduler. More...
 
class  Setup
 Holds the setup configuration for Flight Executive. More...
 
class  StorageManager
 App which manages all storage output from the flight system. More...
 
struct  PacketTypeInfo
 Telemetry packet type metadata struct. More...
 
struct  PacketInfo
 Telemetry packet metadata struct. More...
 
class  TelemetryManager
 App which manages all telemetry output from the flight system. More...
 
class  Rates
 
class  Dynamics
 
class  EkfMeasurementUpdate
 Generic, templated EKF measurement update class. More...
 
class  EkfTimeUpdate
 
class  GPSMeasurements
 
class  InertialNavigationDynamics
 
class  Measurements
 
class  PointingVectorMeasurements
 
class  ForwardEulerIntegrator
 
class  Integrator
 
class  RK4Integrator
 
class  TableScheduler
 Simple, table-based scheduler for flight software. More...
 

Enumerations

enum  tlm_priority_e : uint8 { NORMAL = 0 , HIGH = 1 }
 Enumeration of valid telemtry queue priorities. More...
 

Functions

int16 computeCRC16 (uint32 &crc, const uint8 *packet_ptr, size_t length, uint32 input_crc=0)
 Function to compute the CRC16 checksum for a packet. More...
 
int16 validateCRC16 (uint32 &crc, const uint8 *packet_ptr, size_t length, uint32 input_crc=0)
 Function to validate the CRC16 checksum for a packet. More...
 
int16 writeCCSDSHeader (uint8 *header, bool is_tlm, uint16 apid, uint8 seq_flag, uint16 seq_count, uint16 data_len, clockwerk::Time timestamp, uint8 instance)
 Function to write the CCSDS packet header. More...
 
int16 readCCSDSHeader (uint8 *header, bool &is_tlm, uint16 &apid, uint8 &seq_flag, uint16 &seq_count, uint16 &data_len, clockwerk::Time &timestamp, uint8 &instance)
 Function to read the CCSDS packet header and extract its contents. More...
 
template<class T >
changeEndian (T in)
 Change the endianness of a number. More...
 
template<class T , std::size_t N>
std::array< T, N > changeEndian (const std::array< T, N > &in)
 Specialized version of changeEndian which manages array values correctly. More...
 
 EXCLUDE_FROM_COVERAGE (const FlightExecutive &FlightExecutive::operator=(const FlightExecutive &original) { return *this;}) FlightExecutive
 
const clockwerk::Time TLM_RATE_NEVER (UINT32_MAX, 0)
 Pre-defined constant for never sending tlm packet for clarity and ease of use. More...
 
const clockwerk::Time TLM_RATE_ALWAYS (0, 0)
 Pre-defined constant for always sending tlm packet for clarity and ease of use. More...
 
void convertImuInertialCg (const clockwerk::CartesianVector< 3 > &accel_meas_imu_I__imu, const clockwerk::CartesianVector< 3 > &ang_vel_meas_imu_I__imu, const clockwerk::CartesianVector< 3 > &ang_accel_meas_imu_I__imu, const clockwerk::CartesianVector< 3 > &lever_arm_imu_body__body, const clockwerk::Quaternion &quat_imu_body, const clockwerk::CartesianVector< 3 > &accel_bias__imu, const clockwerk::CartesianVector< 3 > &ang_vel_bias__imu, clockwerk::CartesianVector< 3 > &accel_body_I__body, clockwerk::CartesianVector< 3 > &ang_vel_body_I__body)
 Rotate IMU measurement from IMU frame to inertial body representation. More...
 
const uint32 GPS_MEASUREMENT_VECTOR_ELEMENTS (3)
 
const uint32 GPS_MEASUREMENT_OBSERVER_VECTOR_ELEMENTS (4)
 
const uint32 GPS_MEASUREMENT_MEASUREMENT_NOISE_ELEMENTS (3)
 
const uint32 INERTIAL_NAVIGATION_STATE_VECTOR_ELEMENTS (3+3+4+3+3)
 
const uint32 INERTIAL_NAVIGATION_OBSERVER_VECTOR_ELEMENTS (3+3+3+3)
 
const uint32 INERTIAL_NAVIGATION_PROCESS_NOISE_ELEMENTS (3+3+4+3+3)
 
const clockwerk::CartesianVector< 3 > CONSTANT_BIAS_DYNAMICS ({0.0, 0.0, 0.0})
 
const uint32 POINTING_MEASUREMENT_MEASUREMENT_VECTOR_ELEMENTS (3)
 
const uint32 POINTING_MEASUREMENT_OBSERVER_VECTOR_ELEMENTS (3+4)
 
const uint32 POINTING_MEASUREMENT_MEASUREMENT_NOISE_ELEMENTS (3)
 
int16 pcrToDeticLla (clockwerk::CartesianVector< 3 > pos__pcr, floating_point r_planet_equatorial, floating_point flattening, floating_point &lat_rad, floating_point &lon_rad, floating_point &alt, uint8 max_iter=50, floating_point tolerance=100.0 *1e-6)
 Function to calculate detic LLA from PCR state. More...
 
int16 llaDeticToPCR (floating_point r_planet_equitorial, floating_point flattening, floating_point lat_rad, floating_point lon_rad, floating_point alt, clockwerk::CartesianVector< 3 > &pos__pcr)
 Function to return the PCR (planet centered rotating) position of an object from detic latitude, longitude, and altitude. More...
 
clockwerk::DCM enuFromLatLonDetic (floating_point lat_rad, floating_point lon_rad)
 Function to calculate the East, North, Up frame attitude from detic lat and lon. More...
 
clockwerk::DCM nedFromLatLonDetic (floating_point lat_rad, floating_point lon_rad)
 Function to calculate the North, East, Down frame attitude from detic lat and lon. More...
 

Variables

const clockwerk::CartesianVector< 3 > ZERO_VECTOR = clockwerk::CartesianVector<3>({0.0, 0.0, 0.0})
 Zero vector. More...
 
const floating_point NSEC_TO_BIT32 = (0xFFFFFFFF) / clockwerk::NSEC_PER_SEC_I
 Factor to convert nanoseconds to 2^-32 seconds. More...
 
PlanetDefaults earth_wgs84
 
PlanetDefaults moon_nasa
 
PlanetDefaults sun_nasa
 
PlanetDefaults mercury_nasa
 
PlanetDefaults venus_nasa
 
PlanetDefaults mars_nasa
 
PlanetDefaults jupiter_nasa
 
PlanetDefaults uranus_nasa
 
PlanetDefaults neptune_nasa
 
std::vector< PlanetDefaults * > defined_planet_defaults = {&earth_wgs84, &moon_nasa, &sun_nasa, &mercury_nasa, &venus_nasa, &mars_nasa, &jupiter_nasa, &uranus_nasa, &neptune_nasa}
 A single container to hold all defaults for searchability. More...
 
const floating_point TWO_PI = 2.0*M_PI
 
const floating_point DEGREES_TO_RADIANS = M_PI/180.0
 
const floating_point RADIANS_TO_DEGREES = 180.0/M_PI
 
const floating_point SPEED_OF_LIGHT = 299792458.0
 
const floating_point BOLTZMANN_CONSTANT = 1.380649e-23
 
const floating_point AU_TO_METERS = 149597870700.0
 
const floating_point METERS_TO_AU = 1.0/149597870700.0
 
const floating_point KM_TO_METERS = 1000.0
 
const floating_point METERS_TO_KM = 0.001
 
const floating_point METERS_TO_FEET = 3.28084
 
const floating_point FEET_TO_METERS = 1.0/METERS_TO_FEET
 
const double METERS_TO_NAUTICAL_MILES = 1.0/1852.0
 
const double LBS_TO_KG = 0.45359237
 
const double KG_TO_LBS = 1.0 / LBS_TO_KG
 
const double POUND_FORCE_INCH_SECOND2_TO_METER2_KG = 0.1129848
 
const floating_point MINUTES_TO_SECONDS = 60.0
 
const floating_point HOURS_TO_SECONDS = MINUTES_TO_SECONDS*MINUTES_TO_SECONDS
 
const floating_point DAYS_TO_SECONDS = 24.0*HOURS_TO_SECONDS
 
const floating_point YEARS_TO_SECONDS = 365.25*DAYS_TO_SECONDS
 
const floating_point PSI_TO_PASCAL = 6894.7572932
 
const floating_point PASCAL_TO_PSI = 1.0/PSI_TO_PASCAL
 
const uint8 PRINT_SIZE = 200
 
const uint8 TIME_STR_SIZE = 20
 Constant for time string conversion. More...
 
const clockwerk::Matrix< 3, 3 > IDENTITY ({ {1.0, 0.0, 0.0}, {0.0, 1.0, 0.0}, {0.0, 0.0, 1.0} }) = clockwerk::Matrix<3, 3>({{1.0, 0.0, 0.0},{0.0, 1.0, 0.0},{0.0, 0.0, 1.0}})
 Identity matrix used in computations. More...
 
const std::array< floating_point, INERTIAL_NAVIGATION_STATE_VECTOR_ELEMENTS *INERTIAL_NAVIGATION_PROCESS_NOISE_ELEMENTSCONSTANT_MAPPING_MATRIX_INERTIAL_NAVIGATION
 
const std::array< floating_point, INERTIAL_NAVIGATION_OBSERVER_VECTOR_ELEMENTSCONSTANT_OBSERVER_DYNAMICS = {0.0}
 

Enumeration Type Documentation

◆ tlm_priority_e

enum cfspp::tlm_priority_e : uint8

Enumeration of valid telemtry queue priorities.

Enumerator
NORMAL 
HIGH 

Function Documentation

◆ changeEndian() [1/2]

template<class T , std::size_t N>
std::array<T, N> cfspp::changeEndian ( const std::array< T, N > &  in)

Specialized version of changeEndian which manages array values correctly.

◆ changeEndian() [2/2]

template<class T >
T cfspp::changeEndian ( in)

Change the endianness of a number.

Parameters
inThe number to change endianness of
Returns
The number with endianness swapped

◆ computeCRC16()

int16 cfspp::computeCRC16 ( uint32 &  crc,
const uint8 *  packet_ptr,
size_t  length,
uint32  input_crc = 0 
)

Function to compute the CRC16 checksum for a packet.

Parameters
crcCRC16 checksum PBR
packet_ptrPointer to the packet
lengthLength of the packet in bytes
input_crcStarting/seed value for use in the CRC calculation
Returns
Error code corresponding to success/failure
Note
This function assumes that the packet_ptr buffer is in a directly-accessible memory space

◆ CONSTANT_BIAS_DYNAMICS()

const clockwerk::CartesianVector<3> cfspp::CONSTANT_BIAS_DYNAMICS ( {0.0, 0.0, 0.0}  )

◆ convertImuInertialCg()

void cfspp::convertImuInertialCg ( const clockwerk::CartesianVector< 3 > &  accel_meas_imu_I__imu,
const clockwerk::CartesianVector< 3 > &  ang_vel_meas_imu_I__imu,
const clockwerk::CartesianVector< 3 > &  ang_accel_meas_imu_I__imu,
const clockwerk::CartesianVector< 3 > &  lever_arm_imu_body__body,
const clockwerk::Quaternion quat_imu_body,
const clockwerk::CartesianVector< 3 > &  accel_bias__imu,
const clockwerk::CartesianVector< 3 > &  ang_vel_bias__imu,
clockwerk::CartesianVector< 3 > &  accel_body_I__body,
clockwerk::CartesianVector< 3 > &  ang_vel_body_I__body 
)

Rotate IMU measurement from IMU frame to inertial body representation.

Parameters
accel_meas_imu_I__imuThe acceleration measured by the IMU
ang_vel_meas_imu_I__imuThe angular velocity measured by the IMU
ang_accel_meas_imu_I__imuThe angular acceleration measured by the IMU, often derived from differencing ang vel.
lever_arm_imu_body__bodyThe lever arm from the body CG to the IMU frame, represented in body coords
quat_imu_bodyThe quaternion describing the orientation of the IMU frame wrt the body frame
accel_bias__imuThe IMU acceleration bias as measured in the imu frame
ang_vel_bias__imuThe angular velocity bias as measured in the imu frame
accel_body_I__bodyImplicit return of inertial acceleration as measured in body frame
ang_vel_body_I__bodyImplicit return of inertial angular velocity as measured in body frame
accel_meas__imuThe acceleration measured by the IMU
ang_vel_meas__imuThe angular velocity measured by the IMU
ang_accel_meas__imuThe angular acceleration measured by the IMU, often derived from differencing ang vel.
lever_arm__bodyThe lever arm from the body CG to the IMU frame, represented in body coords
quat_imu_bodyThe quaternion describing the orientation of the IMU frame wrt the body frame
accel_bias__imuThe IMU acceleration bias as measured in the imu frame
ang_vel_bias__imuThe angular velocity bias as measured in the imu frame
accel_inrtl__bodyImplicit return of inertial acceleration as measured in body frame
ang_vel_inrtl__bodyImplicit return of inertial angular velocity as measured in body frame

◆ enuFromLatLonDetic()

clockwerk::DCM cfspp::enuFromLatLonDetic ( floating_point  lat_rad,
floating_point  lon_rad 
)

Function to calculate the East, North, Up frame attitude from detic lat and lon.

Parameters
lat_radThe detic latitude in radians
lon_radThe longitude in radians
Returns
DCM corresponding to ENU frame attitude relative to PCR

◆ EXCLUDE_FROM_COVERAGE()

cfspp::EXCLUDE_FROM_COVERAGE ( const FlightExecutive &FlightExecutive::operator  = (const FlightExecutive& original) { return *this; })

◆ GPS_MEASUREMENT_MEASUREMENT_NOISE_ELEMENTS()

const uint32 cfspp::GPS_MEASUREMENT_MEASUREMENT_NOISE_ELEMENTS ( )

◆ GPS_MEASUREMENT_OBSERVER_VECTOR_ELEMENTS()

const uint32 cfspp::GPS_MEASUREMENT_OBSERVER_VECTOR_ELEMENTS ( )

◆ GPS_MEASUREMENT_VECTOR_ELEMENTS()

const uint32 cfspp::GPS_MEASUREMENT_VECTOR_ELEMENTS ( )

◆ INERTIAL_NAVIGATION_OBSERVER_VECTOR_ELEMENTS()

const uint32 cfspp::INERTIAL_NAVIGATION_OBSERVER_VECTOR_ELEMENTS ( 3+3+3+  3)

◆ INERTIAL_NAVIGATION_PROCESS_NOISE_ELEMENTS()

const uint32 cfspp::INERTIAL_NAVIGATION_PROCESS_NOISE_ELEMENTS ( 3+3+4+3+  3)

◆ INERTIAL_NAVIGATION_STATE_VECTOR_ELEMENTS()

const uint32 cfspp::INERTIAL_NAVIGATION_STATE_VECTOR_ELEMENTS ( 3+3+4+3+  3)

◆ llaDeticToPCR()

int16 cfspp::llaDeticToPCR ( floating_point  r_planet_equitorial,
floating_point  flattening,
floating_point  lat_rad,
floating_point  lon_rad,
floating_point  alt,
clockwerk::CartesianVector< 3 > &  pos__pcr 
)

Function to return the PCR (planet centered rotating) position of an object from detic latitude, longitude, and altitude.

Parameters
r_planet_equitorialThe equatorial radius of the planet
flatteningFlattening coefficient of the planet
lat_radThe detic latitude in radians
lon_radThe longitude in radians
altThe detic altitude in the same units as the radius (r_planet)
pos__pcrImplicit return of the position of the object in PCR coordinates
Returns
Error code (0 if no error occurs)
Note
Method based on equation 3.6 in chapter 3 section 2, equation 10.1-10.2 in chapter 10 section 2.1 from Global Positioning System Theory and Practice by B. Hofmann-Wellenhof, H. Lichtenegger, and J. Collins

◆ nedFromLatLonDetic()

clockwerk::DCM cfspp::nedFromLatLonDetic ( floating_point  lat_rad,
floating_point  lon_rad 
)

Function to calculate the North, East, Down frame attitude from detic lat and lon.

Parameters
lat_radThe detic latitude in radians
lon_radThe longitude in radians
Returns
DCM corresponding to NED frame attitude relative to PCR

◆ pcrToDeticLla()

int16 cfspp::pcrToDeticLla ( clockwerk::CartesianVector< 3 >  pos__pcr,
floating_point  r_planet_equatorial,
floating_point  flattening,
floating_point &  lat_rad,
floating_point &  lon_rad,
floating_point &  alt,
uint8  max_iter = 50,
floating_point  tolerance = 100.0 *1e-6 
)

Function to calculate detic LLA from PCR state.

Parameters
pos__pcrThe position of the spacecraft in PCR frame
r_planet_equatorialThe equatorial radius of the planet
flatteningThe flattening value of the planet
lat_radImplicit return of latitude in radians
lon_radImplicit return of longitude in radians
altImplicit return of altitude
max_iterThe maximum number of iterations which can occur in the convergence loop
toleranceThe tolerance which must be achieved for convergence
Returns
Error code corresponding to success/failure

◆ POINTING_MEASUREMENT_MEASUREMENT_NOISE_ELEMENTS()

const uint32 cfspp::POINTING_MEASUREMENT_MEASUREMENT_NOISE_ELEMENTS ( )

◆ POINTING_MEASUREMENT_MEASUREMENT_VECTOR_ELEMENTS()

const uint32 cfspp::POINTING_MEASUREMENT_MEASUREMENT_VECTOR_ELEMENTS ( )

◆ POINTING_MEASUREMENT_OBSERVER_VECTOR_ELEMENTS()

const uint32 cfspp::POINTING_MEASUREMENT_OBSERVER_VECTOR_ELEMENTS ( 3+  4)

◆ readCCSDSHeader()

int16 cfspp::readCCSDSHeader ( uint8 *  header,
bool &  is_tlm,
uint16 &  apid,
uint8 &  seq_flag,
uint16 &  seq_count,
uint16 &  data_len,
clockwerk::Time timestamp,
uint8 &  instance 
)

Function to read the CCSDS packet header and extract its contents.

Parameters
headerPointer to the head of the buffer that holds the header (must be at least 6 bytes long)
is_tlmPacket type bit PBR
apidPacket APID PBR
seq_flagSequence flag PBR
seq_countSequence count PBR
data_lenPacket data length PBR
timestampTime of the packet from secondary header time code PBR
instanceAPID instance from secondary header PBR
Returns
Error code corresponding to success/failure

◆ TLM_RATE_ALWAYS()

const clockwerk::Time cfspp::TLM_RATE_ALWAYS ( ,
 
)

Pre-defined constant for always sending tlm packet for clarity and ease of use.

◆ TLM_RATE_NEVER()

const clockwerk::Time cfspp::TLM_RATE_NEVER ( UINT32_MAX  ,
 
)

Pre-defined constant for never sending tlm packet for clarity and ease of use.

◆ validateCRC16()

int16 cfspp::validateCRC16 ( uint32 &  crc,
const uint8 *  packet_ptr,
size_t  length,
uint32  input_crc = 0 
)

Function to validate the CRC16 checksum for a packet.

Parameters
crcCRC16 checksum to validate
packet_ptrPointer to the packet
lengthLength of the packet in bytes
input_crcStarting/seed value for use in the CRC calculation
Returns
Error code corresponding to success/failure
Note
This function assumes that the packet_ptr buffer is in a directly-accessible memory space

◆ writeCCSDSHeader()

int16 cfspp::writeCCSDSHeader ( uint8 *  header,
bool  is_tlm,
uint16  apid,
uint8  seq_flag,
uint16  seq_count,
uint16  data_len,
clockwerk::Time  timestamp,
uint8  instance 
)

Function to write the CCSDS packet header.

Parameters
headerPointer to the head of the buffer that will hold the header (must be at least 12 bytes long for both primary and secondary headers)
is_tlmWhether or not this is a telemetry packet, for packet type bit
apidPacket APID
seq_flagSequence flag
seq_countSequence count
data_lenPacket data length in bytes (not length - 1 as specified by CCSDS standard; this function will subtract 1)
timestampTime of the packet for secondary header time code
instanceAPID instance for secondary header
Returns
Error code corresponding to success/failure
Note
The CCSDS header will have a primary header as well as a secondary header containing a time code, which is formatted per cFS implementation

Variable Documentation

◆ AU_TO_METERS

const floating_point cfspp::AU_TO_METERS = 149597870700.0

◆ BOLTZMANN_CONSTANT

const floating_point cfspp::BOLTZMANN_CONSTANT = 1.380649e-23

◆ CONSTANT_MAPPING_MATRIX_INERTIAL_NAVIGATION

const std::array<floating_point, INERTIAL_NAVIGATION_STATE_VECTOR_ELEMENTS*INERTIAL_NAVIGATION_PROCESS_NOISE_ELEMENTS> cfspp::CONSTANT_MAPPING_MATRIX_INERTIAL_NAVIGATION
Initial value:
= {
1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0,
}

◆ CONSTANT_OBSERVER_DYNAMICS

const std::array<floating_point, INERTIAL_NAVIGATION_OBSERVER_VECTOR_ELEMENTS> cfspp::CONSTANT_OBSERVER_DYNAMICS = {0.0}

◆ DAYS_TO_SECONDS

const floating_point cfspp::DAYS_TO_SECONDS = 24.0*HOURS_TO_SECONDS

◆ defined_planet_defaults

std::vector< PlanetDefaults * > cfspp::defined_planet_defaults = {&earth_wgs84, &moon_nasa, &sun_nasa, &mercury_nasa, &venus_nasa, &mars_nasa, &jupiter_nasa, &uranus_nasa, &neptune_nasa}

A single container to hold all defaults for searchability.

◆ DEGREES_TO_RADIANS

const floating_point cfspp::DEGREES_TO_RADIANS = M_PI/180.0

◆ earth_wgs84

PlanetDefaults cfspp::earth_wgs84
Initial value:
= {
"EARTH",
6378137.0,
1.0/298.257223563,
3.986004418e14,
0.00108262998905,
-0.00000253215306,
7.292115e-5,
9.7976432223
}

◆ FEET_TO_METERS

const floating_point cfspp::FEET_TO_METERS = 1.0/METERS_TO_FEET

◆ HOURS_TO_SECONDS

const floating_point cfspp::HOURS_TO_SECONDS = MINUTES_TO_SECONDS*MINUTES_TO_SECONDS

◆ IDENTITY

const clockwerk::Matrix< 3, 3 > cfspp::IDENTITY ( { {1.0, 0.0, 0.0}, {0.0, 1.0, 0.0}, {0.0, 0.0, 1.0} }  ) = clockwerk::Matrix<3, 3>({{1.0, 0.0, 0.0},{0.0, 1.0, 0.0},{0.0, 0.0, 1.0}})

Identity matrix used in computations.

◆ jupiter_nasa

PlanetDefaults cfspp::jupiter_nasa
Initial value:
= {
"JUPITER",
71492000.0,
0.06487,
1.26687e17,
0.014736,
0.0,
static_cast<floating_point>(TWO_PI/(9.9250*HOURS_TO_SECONDS)),
25.92
}
const floating_point TWO_PI
Definition: unitutils.h:26
const floating_point HOURS_TO_SECONDS
Definition: unitutils.h:58

◆ KG_TO_LBS

const double cfspp::KG_TO_LBS = 1.0 / LBS_TO_KG

◆ KM_TO_METERS

const floating_point cfspp::KM_TO_METERS = 1000.0

◆ LBS_TO_KG

const double cfspp::LBS_TO_KG = 0.45359237

◆ mars_nasa

PlanetDefaults cfspp::mars_nasa
Initial value:
= {
"MARS",
3396200.0,
0.00589,
4.2828e13,
0.00196045,
0.0,
static_cast<floating_point>(TWO_PI/(24.6229*HOURS_TO_SECONDS)),
3.73
}

◆ mercury_nasa

PlanetDefaults cfspp::mercury_nasa
Initial value:
= {
"MERCURY",
2440500.0,
0.0009,
2.2032e13,
0.00005030,
0.0,
static_cast<floating_point>(TWO_PI/(1407.6*HOURS_TO_SECONDS)),
3.70
}

◆ METERS_TO_AU

const floating_point cfspp::METERS_TO_AU = 1.0/149597870700.0

◆ METERS_TO_FEET

const floating_point cfspp::METERS_TO_FEET = 3.28084

◆ METERS_TO_KM

const floating_point cfspp::METERS_TO_KM = 0.001

◆ METERS_TO_NAUTICAL_MILES

const double cfspp::METERS_TO_NAUTICAL_MILES = 1.0/1852.0

◆ MINUTES_TO_SECONDS

const floating_point cfspp::MINUTES_TO_SECONDS = 60.0

◆ moon_nasa

PlanetDefaults cfspp::moon_nasa
Initial value:
= {
"MOON",
1738100.0,
0.0012,
4.90e12,
0.0002027,
0.0,
static_cast<floating_point>(TWO_PI/(655.720*HOURS_TO_SECONDS)),
1.62
}

◆ neptune_nasa

PlanetDefaults cfspp::neptune_nasa
Initial value:
= {
"NEPTUNE",
24764000.0,
0.01708,
6.8351e15,
0.003411,
0.0,
static_cast<floating_point>(TWO_PI/(16.11*HOURS_TO_SECONDS)),
11.27
}

◆ NSEC_TO_BIT32

const floating_point cfspp::NSEC_TO_BIT32 = (0xFFFFFFFF) / clockwerk::NSEC_PER_SEC_I

Factor to convert nanoseconds to 2^-32 seconds.

◆ PASCAL_TO_PSI

const floating_point cfspp::PASCAL_TO_PSI = 1.0/PSI_TO_PASCAL

◆ POUND_FORCE_INCH_SECOND2_TO_METER2_KG

const double cfspp::POUND_FORCE_INCH_SECOND2_TO_METER2_KG = 0.1129848

◆ PRINT_SIZE

const uint8 cfspp::PRINT_SIZE = 200

◆ PSI_TO_PASCAL

const floating_point cfspp::PSI_TO_PASCAL = 6894.7572932

◆ RADIANS_TO_DEGREES

const floating_point cfspp::RADIANS_TO_DEGREES = 180.0/M_PI

◆ SPEED_OF_LIGHT

const floating_point cfspp::SPEED_OF_LIGHT = 299792458.0

◆ sun_nasa

PlanetDefaults cfspp::sun_nasa
Initial value:
= {
"SUN",
695700000.0,
0.00005,
1.32712e20,
0.0,
0.0,
static_cast<floating_point>(TWO_PI/(609.12*HOURS_TO_SECONDS)),
274.0
}

◆ TIME_STR_SIZE

const uint8 cfspp::TIME_STR_SIZE = 20

Constant for time string conversion.

◆ TWO_PI

const floating_point cfspp::TWO_PI = 2.0*M_PI

◆ uranus_nasa

PlanetDefaults cfspp::uranus_nasa
Initial value:
= {
"URANUS",
25559000.0,
0.02293,
5.7940e15,
0.00334343,
0.0,
static_cast<floating_point>(-TWO_PI/(17.24*HOURS_TO_SECONDS)),
9.01
}

◆ venus_nasa

PlanetDefaults cfspp::venus_nasa
Initial value:
= {
"VENUS",
6051800.0,
0.0,
3.2486e14,
0.000004458,
0.0,
static_cast<floating_point>(-TWO_PI/(5832.6*HOURS_TO_SECONDS)),
8.87
}

◆ YEARS_TO_SECONDS

const floating_point cfspp::YEARS_TO_SECONDS = 365.25*DAYS_TO_SECONDS

◆ ZERO_VECTOR

const clockwerk::CartesianVector< 3 > cfspp::ZERO_VECTOR = clockwerk::CartesianVector<3>({0.0, 0.0, 0.0})

Zero vector.