![]() |
ModelSpace
Documentation for ModelSpace models and classes.
|
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 ×tamp, uint8 &instance) |
| Function to read the CCSDS packet header and extract its contents. More... | |
| template<class T > | |
| 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_ELEMENTS > | CONSTANT_MAPPING_MATRIX_INERTIAL_NAVIGATION |
| const std::array< floating_point, INERTIAL_NAVIGATION_OBSERVER_VECTOR_ELEMENTS > | CONSTANT_OBSERVER_DYNAMICS = {0.0} |
| enum cfspp::tlm_priority_e : uint8 |
| std::array<T, N> cfspp::changeEndian | ( | const std::array< T, N > & | in | ) |
Specialized version of changeEndian which manages array values correctly.
| T cfspp::changeEndian | ( | T | in | ) |
Change the endianness of a number.
| in | The number to change endianness of |
| 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.
| crc | CRC16 checksum PBR |
| packet_ptr | Pointer to the packet |
| length | Length of the packet in bytes |
| input_crc | Starting/seed value for use in the CRC calculation |
| const clockwerk::CartesianVector<3> cfspp::CONSTANT_BIAS_DYNAMICS | ( | {0.0, 0.0, 0.0} | ) |
| 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.
| accel_meas_imu_I__imu | The acceleration measured by the IMU |
| ang_vel_meas_imu_I__imu | The angular velocity measured by the IMU |
| ang_accel_meas_imu_I__imu | The angular acceleration measured by the IMU, often derived from differencing ang vel. |
| lever_arm_imu_body__body | The lever arm from the body CG to the IMU frame, represented in body coords |
| quat_imu_body | The quaternion describing the orientation of the IMU frame wrt the body frame |
| accel_bias__imu | The IMU acceleration bias as measured in the imu frame |
| ang_vel_bias__imu | The angular velocity bias as measured in the imu frame |
| accel_body_I__body | Implicit return of inertial acceleration as measured in body frame |
| ang_vel_body_I__body | Implicit return of inertial angular velocity as measured in body frame |
| accel_meas__imu | The acceleration measured by the IMU |
| ang_vel_meas__imu | The angular velocity measured by the IMU |
| ang_accel_meas__imu | The angular acceleration measured by the IMU, often derived from differencing ang vel. |
| lever_arm__body | The lever arm from the body CG to the IMU frame, represented in body coords |
| quat_imu_body | The quaternion describing the orientation of the IMU frame wrt the body frame |
| accel_bias__imu | The IMU acceleration bias as measured in the imu frame |
| ang_vel_bias__imu | The angular velocity bias as measured in the imu frame |
| accel_inrtl__body | Implicit return of inertial acceleration as measured in body frame |
| ang_vel_inrtl__body | Implicit return of inertial angular velocity as measured in body frame |
| 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.
| lat_rad | The detic latitude in radians |
| lon_rad | The longitude in radians |
| cfspp::EXCLUDE_FROM_COVERAGE | ( | const FlightExecutive &FlightExecutive::operator | = (const FlightExecutive& original) { return *this; } | ) |
| const uint32 cfspp::GPS_MEASUREMENT_MEASUREMENT_NOISE_ELEMENTS | ( | 3 | ) |
| const uint32 cfspp::GPS_MEASUREMENT_OBSERVER_VECTOR_ELEMENTS | ( | 4 | ) |
| const uint32 cfspp::GPS_MEASUREMENT_VECTOR_ELEMENTS | ( | 3 | ) |
| const uint32 cfspp::INERTIAL_NAVIGATION_OBSERVER_VECTOR_ELEMENTS | ( | 3+3+3+ | 3 | ) |
| const uint32 cfspp::INERTIAL_NAVIGATION_PROCESS_NOISE_ELEMENTS | ( | 3+3+4+3+ | 3 | ) |
| const uint32 cfspp::INERTIAL_NAVIGATION_STATE_VECTOR_ELEMENTS | ( | 3+3+4+3+ | 3 | ) |
| 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.
| r_planet_equitorial | The equatorial radius of the planet |
| flattening | Flattening coefficient of the planet |
| lat_rad | The detic latitude in radians |
| lon_rad | The longitude in radians |
| alt | The detic altitude in the same units as the radius (r_planet) |
| pos__pcr | Implicit return of the position of the object in PCR coordinates |
| 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.
| lat_rad | The detic latitude in radians |
| lon_rad | The longitude in radians |
| 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.
| pos__pcr | The position of the spacecraft in PCR frame |
| r_planet_equatorial | The equatorial radius of the planet |
| flattening | The flattening value of the planet |
| lat_rad | Implicit return of latitude in radians |
| lon_rad | Implicit return of longitude in radians |
| alt | Implicit return of altitude |
| max_iter | The maximum number of iterations which can occur in the convergence loop |
| tolerance | The tolerance which must be achieved for convergence |
| const uint32 cfspp::POINTING_MEASUREMENT_MEASUREMENT_NOISE_ELEMENTS | ( | 3 | ) |
| const uint32 cfspp::POINTING_MEASUREMENT_MEASUREMENT_VECTOR_ELEMENTS | ( | 3 | ) |
| const uint32 cfspp::POINTING_MEASUREMENT_OBSERVER_VECTOR_ELEMENTS | ( | 3+ | 4 | ) |
| 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.
| header | Pointer to the head of the buffer that holds the header (must be at least 6 bytes long) |
| is_tlm | Packet type bit PBR |
| apid | Packet APID PBR |
| seq_flag | Sequence flag PBR |
| seq_count | Sequence count PBR |
| data_len | Packet data length PBR |
| timestamp | Time of the packet from secondary header time code PBR |
| instance | APID instance from secondary header PBR |
| const clockwerk::Time cfspp::TLM_RATE_ALWAYS | ( | 0 | , |
| 0 | |||
| ) |
Pre-defined constant for always sending tlm packet for clarity and ease of use.
| const clockwerk::Time cfspp::TLM_RATE_NEVER | ( | UINT32_MAX | , |
| 0 | |||
| ) |
Pre-defined constant for never sending tlm packet for clarity and ease of use.
| 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.
| crc | CRC16 checksum to validate |
| packet_ptr | Pointer to the packet |
| length | Length of the packet in bytes |
| input_crc | Starting/seed value for use in the CRC calculation |
| 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.
| header | Pointer 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_tlm | Whether or not this is a telemetry packet, for packet type bit |
| apid | Packet APID |
| seq_flag | Sequence flag |
| seq_count | Sequence count |
| data_len | Packet data length in bytes (not length - 1 as specified by CCSDS standard; this function will subtract 1) |
| timestamp | Time of the packet for secondary header time code |
| instance | APID instance for secondary header |
| const floating_point cfspp::AU_TO_METERS = 149597870700.0 |
| const floating_point cfspp::BOLTZMANN_CONSTANT = 1.380649e-23 |
| const std::array<floating_point, INERTIAL_NAVIGATION_STATE_VECTOR_ELEMENTS*INERTIAL_NAVIGATION_PROCESS_NOISE_ELEMENTS> cfspp::CONSTANT_MAPPING_MATRIX_INERTIAL_NAVIGATION |
| const std::array<floating_point, INERTIAL_NAVIGATION_OBSERVER_VECTOR_ELEMENTS> cfspp::CONSTANT_OBSERVER_DYNAMICS = {0.0} |
| const floating_point cfspp::DAYS_TO_SECONDS = 24.0*HOURS_TO_SECONDS |
| 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.
| const floating_point cfspp::DEGREES_TO_RADIANS = M_PI/180.0 |
| PlanetDefaults cfspp::earth_wgs84 |
| const floating_point cfspp::FEET_TO_METERS = 1.0/METERS_TO_FEET |
| const floating_point cfspp::HOURS_TO_SECONDS = MINUTES_TO_SECONDS*MINUTES_TO_SECONDS |
| 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.
| PlanetDefaults cfspp::jupiter_nasa |
| const double cfspp::KG_TO_LBS = 1.0 / LBS_TO_KG |
| const floating_point cfspp::KM_TO_METERS = 1000.0 |
| const double cfspp::LBS_TO_KG = 0.45359237 |
| PlanetDefaults cfspp::mars_nasa |
| PlanetDefaults cfspp::mercury_nasa |
| const floating_point cfspp::METERS_TO_AU = 1.0/149597870700.0 |
| const floating_point cfspp::METERS_TO_FEET = 3.28084 |
| const floating_point cfspp::METERS_TO_KM = 0.001 |
| const double cfspp::METERS_TO_NAUTICAL_MILES = 1.0/1852.0 |
| const floating_point cfspp::MINUTES_TO_SECONDS = 60.0 |
| PlanetDefaults cfspp::moon_nasa |
| PlanetDefaults cfspp::neptune_nasa |
| const floating_point cfspp::NSEC_TO_BIT32 = (0xFFFFFFFF) / clockwerk::NSEC_PER_SEC_I |
Factor to convert nanoseconds to 2^-32 seconds.
| const floating_point cfspp::PASCAL_TO_PSI = 1.0/PSI_TO_PASCAL |
| const double cfspp::POUND_FORCE_INCH_SECOND2_TO_METER2_KG = 0.1129848 |
| const uint8 cfspp::PRINT_SIZE = 200 |
| const floating_point cfspp::PSI_TO_PASCAL = 6894.7572932 |
| const floating_point cfspp::RADIANS_TO_DEGREES = 180.0/M_PI |
| const floating_point cfspp::SPEED_OF_LIGHT = 299792458.0 |
| PlanetDefaults cfspp::sun_nasa |
| const uint8 cfspp::TIME_STR_SIZE = 20 |
Constant for time string conversion.
| const floating_point cfspp::TWO_PI = 2.0*M_PI |
| PlanetDefaults cfspp::uranus_nasa |
| PlanetDefaults cfspp::venus_nasa |
| const floating_point cfspp::YEARS_TO_SECONDS = 365.25*DAYS_TO_SECONDS |
| const clockwerk::CartesianVector< 3 > cfspp::ZERO_VECTOR = clockwerk::CartesianVector<3>({0.0, 0.0, 0.0}) |
Zero vector.