From d5216018caa653ab8074462bc2861475f9357302 Mon Sep 17 00:00:00 2001 From: Satoshi Ikari Date: Sat, 20 Jul 2024 11:05:23 +0900 Subject: [PATCH] Add randomization namespace --- src/components/base/sensor.hpp | 2 +- src/components/ideal/attitude_observer.hpp | 4 ++-- src/components/ideal/force_generator.hpp | 4 ++-- src/components/ideal/orbit_observer.hpp | 2 +- src/components/ideal/torque_generator.hpp | 4 ++-- src/components/real/aocs/gnss_receiver.hpp | 4 ++-- src/components/real/aocs/magnetorquer.hpp | 2 +- src/components/real/aocs/star_sensor.hpp | 6 +++--- src/components/real/aocs/sun_sensor.cpp | 2 +- src/components/real/aocs/sun_sensor.hpp | 4 ++-- src/components/real/propulsion/simple_thruster.hpp | 4 ++-- src/disturbances/magnetic_disturbance.cpp | 2 +- src/environment/local/atmosphere.cpp | 2 +- src/environment/local/geomagnetic_field.cpp | 2 +- src/math_physics/randomization/global_randomization.hpp | 2 +- .../minimal_standard_linear_congruential_generator.cpp | 2 +- .../minimal_standard_linear_congruential_generator.hpp | 4 ++-- ..._standard_linear_congruential_generator_with_shuffle.cpp | 2 +- ..._standard_linear_congruential_generator_with_shuffle.hpp | 4 ++-- src/math_physics/randomization/normal_randomization.cpp | 2 +- src/math_physics/randomization/normal_randomization.hpp | 6 +++--- src/math_physics/randomization/random_walk.hpp | 2 +- 22 files changed, 34 insertions(+), 34 deletions(-) diff --git a/src/components/base/sensor.hpp b/src/components/base/sensor.hpp index 883050b19..8562310de 100644 --- a/src/components/base/sensor.hpp +++ b/src/components/base/sensor.hpp @@ -55,7 +55,7 @@ class Sensor { math::Matrix scale_factor_; //!< Scale factor matrix math::Vector range_to_const_c_; //!< Output range limit to be constant output value at the component frame math::Vector range_to_zero_c_; //!< Output range limit to be zero output value at the component frame - libra::NormalRand normal_random_noise_c_[N]; //!< Normal random + randomization::NormalRand normal_random_noise_c_[N]; //!< Normal random RandomWalk random_walk_noise_c_; //!< Random Walk /** diff --git a/src/components/ideal/attitude_observer.hpp b/src/components/ideal/attitude_observer.hpp index 70f571eb8..3244dce32 100644 --- a/src/components/ideal/attitude_observer.hpp +++ b/src/components/ideal/attitude_observer.hpp @@ -62,8 +62,8 @@ class AttitudeObserver : public Component, public ILoggable { protected: math::Quaternion observed_quaternion_i2b_ = {0.0, 0.0, 0.0, 1.0}; //!< Observed quaternion - libra::NormalRand angle_noise_; //!< Normal random for magnitude noise - libra::NormalRand direction_noise_; //!< Normal random for direction noise + randomization::NormalRand angle_noise_; //!< Normal random for magnitude noise + randomization::NormalRand direction_noise_; //!< Normal random for direction noise const Attitude& attitude_; //!< Attitude information }; diff --git a/src/components/ideal/force_generator.hpp b/src/components/ideal/force_generator.hpp index 684f5bab0..c3a5eb6ef 100644 --- a/src/components/ideal/force_generator.hpp +++ b/src/components/ideal/force_generator.hpp @@ -100,8 +100,8 @@ class ForceGenerator : public Component, public ILoggable { math::Vector<3> generated_force_rtn_N_{0.0}; //!< Generated force in the RTN frame [N] // Noise - libra::NormalRand magnitude_noise_; //!< Normal random for magnitude noise - libra::NormalRand direction_noise_; //!< Normal random for direction noise + randomization::NormalRand magnitude_noise_; //!< Normal random for magnitude noise + randomization::NormalRand direction_noise_; //!< Normal random for direction noise double direction_error_standard_deviation_rad_; //!< Standard deviation of direction error [rad] /** diff --git a/src/components/ideal/orbit_observer.hpp b/src/components/ideal/orbit_observer.hpp index c1746af81..09437c079 100644 --- a/src/components/ideal/orbit_observer.hpp +++ b/src/components/ideal/orbit_observer.hpp @@ -82,7 +82,7 @@ class OrbitObserver : public Component, public ILoggable { math::Vector<3> observed_velocity_i_m_s_{0.0}; //!< Observed velocity @ inertial frame [m/s] NoiseFrame noise_frame_; //!< Noise definition frame - libra::NormalRand normal_random_noise_[6]; //!< Position and Velocity noise [m, m/s] + randomization::NormalRand normal_random_noise_[6]; //!< Position and Velocity noise [m, m/s] // Observed variables const Orbit& orbit_; //!< Orbit information diff --git a/src/components/ideal/torque_generator.hpp b/src/components/ideal/torque_generator.hpp index b762fd99e..eb6c01b81 100644 --- a/src/components/ideal/torque_generator.hpp +++ b/src/components/ideal/torque_generator.hpp @@ -78,8 +78,8 @@ class TorqueGenerator : public Component, public ILoggable { math::Vector<3> generated_torque_b_Nm_{0.0}; //!< Generated torque in the body fixed frame [Nm] // Noise - libra::NormalRand magnitude_noise_; //!< Normal random for magnitude noise - libra::NormalRand direction_noise_; //!< Normal random for direction noise + randomization::NormalRand magnitude_noise_; //!< Normal random for magnitude noise + randomization::NormalRand direction_noise_; //!< Normal random for direction noise double direction_error_standard_deviation_rad_; //!< Standard deviation of direction error [rad] /** diff --git a/src/components/real/aocs/gnss_receiver.hpp b/src/components/real/aocs/gnss_receiver.hpp index d418c01d9..9bc48a411 100644 --- a/src/components/real/aocs/gnss_receiver.hpp +++ b/src/components/real/aocs/gnss_receiver.hpp @@ -137,8 +137,8 @@ class GnssReceiver : public Component, public ILoggable { AntennaModel antenna_model_; //!< Antenna model // Simple position observation - libra::NormalRand position_random_noise_ecef_m_[3]; //!< Random noise for position at the ECEF frame [m] - libra::NormalRand velocity_random_noise_ecef_m_s_[3]; //!< Random noise for velocity at the ECEF frame [m] + randomization::NormalRand position_random_noise_ecef_m_[3]; //!< Random noise for position at the ECEF frame [m] + randomization::NormalRand velocity_random_noise_ecef_m_s_[3]; //!< Random noise for velocity at the ECEF frame [m] math::Vector<3> position_ecef_m_{0.0}; //!< Observed position in the ECEF frame [m] math::Vector<3> velocity_ecef_m_s_{0.0}; //!< Observed velocity in the ECEF frame [m/s] GeodeticPosition geodetic_position_; //!< Observed position in the geodetic frame diff --git a/src/components/real/aocs/magnetorquer.hpp b/src/components/real/aocs/magnetorquer.hpp index d424e0c4c..91b91864b 100644 --- a/src/components/real/aocs/magnetorquer.hpp +++ b/src/components/real/aocs/magnetorquer.hpp @@ -134,7 +134,7 @@ class Magnetorquer : public Component, public ILoggable { math::Vector bias_noise_c_Am2_{0.0}; //!< Constant bias noise in the component frame [Am2] RandomWalk random_walk_c_Am2_; //!< Random walk noise - libra::NormalRand random_noise_c_Am2_[kMtqDimension]; //!< Normal random noise + randomization::NormalRand random_noise_c_Am2_[kMtqDimension]; //!< Normal random noise const GeomagneticField* geomagnetic_field_; //!< Geomagnetic environment diff --git a/src/components/real/aocs/star_sensor.hpp b/src/components/real/aocs/star_sensor.hpp index eba0f2ae9..5965c5e9a 100644 --- a/src/components/real/aocs/star_sensor.hpp +++ b/src/components/real/aocs/star_sensor.hpp @@ -115,9 +115,9 @@ class StarSensor : public Component, public ILoggable { math::Vector<3> second_orthogonal_direction_c; //!< The second orthogonal direction of sight at component frame // Noise parameters - libra::MinimalStandardLcgWithShuffle rotation_noise_; //!< Randomize object for orthogonal direction - libra::NormalRand orthogonal_direction_noise_; //!< Random noise for orthogonal direction of sight - libra::NormalRand sight_direction_noise_; //!< Random noise for sight direction + randomization::MinimalStandardLcgWithShuffle rotation_noise_; //!< Randomize object for orthogonal direction + randomization::NormalRand orthogonal_direction_noise_; //!< Random noise for orthogonal direction of sight + randomization::NormalRand sight_direction_noise_; //!< Random noise for sight direction // Delay emulation parameters int max_delay_; //!< Max delay diff --git a/src/components/real/aocs/sun_sensor.cpp b/src/components/real/aocs/sun_sensor.cpp index d4432496b..6b47949ae 100644 --- a/src/components/real/aocs/sun_sensor.cpp +++ b/src/components/real/aocs/sun_sensor.cpp @@ -7,7 +7,7 @@ #include #include -using libra::NormalRand; +using randomization::NormalRand; #include #include #include diff --git a/src/components/real/aocs/sun_sensor.hpp b/src/components/real/aocs/sun_sensor.hpp index 7488e2513..e2c9623fd 100644 --- a/src/components/real/aocs/sun_sensor.hpp +++ b/src/components/real/aocs/sun_sensor.hpp @@ -100,8 +100,8 @@ class SunSensor : public Component, public ILoggable { double detectable_angle_rad_; //!< half angle (>0) [rad] bool sun_detected_flag_ = false; //!< Sun detected flag // Noise parameters - libra::NormalRand random_noise_alpha_; //!< Normal random for alpha angle - libra::NormalRand random_noise_beta_; //!< Normal random for beta angle + randomization::NormalRand random_noise_alpha_; //!< Normal random for alpha angle + randomization::NormalRand random_noise_beta_; //!< Normal random for beta angle double bias_noise_alpha_rad_ = 0.0; //!< Constant bias for alpha angle (Value is calculated by random number generator) double bias_noise_beta_rad_ = 0.0; //!< Constant bias for beta angle (Value is calculated by random number generator) diff --git a/src/components/real/propulsion/simple_thruster.hpp b/src/components/real/propulsion/simple_thruster.hpp index cbceafc71..948a9bdcd 100644 --- a/src/components/real/propulsion/simple_thruster.hpp +++ b/src/components/real/propulsion/simple_thruster.hpp @@ -114,8 +114,8 @@ class SimpleThruster : public Component, public ILoggable { double duty_ = 0.0; //!< PWM Duty [0.0 : 1.0] double thrust_magnitude_max_N_ = 0.0; //!< Maximum thrust magnitude [N] double direction_noise_standard_deviation_rad_ = 0.0; //!< Standard deviation of thrust direction error [rad] - libra::NormalRand magnitude_random_noise_; //!< Normal random for thrust magnitude error - libra::NormalRand direction_random_noise_; //!< Normal random for thrust direction error + randomization::NormalRand magnitude_random_noise_; //!< Normal random for thrust magnitude error + randomization::NormalRand direction_random_noise_; //!< Normal random for thrust direction error // outputs Vector<3> output_thrust_b_N_{0.0}; //!< Generated thrust on the body fixed frame [N] Vector<3> output_torque_b_Nm_{0.0}; //!< Generated torque on the body fixed frame [Nm] diff --git a/src/disturbances/magnetic_disturbance.cpp b/src/disturbances/magnetic_disturbance.cpp index 2b3c4c069..3b49be06c 100644 --- a/src/disturbances/magnetic_disturbance.cpp +++ b/src/disturbances/magnetic_disturbance.cpp @@ -34,7 +34,7 @@ void MagneticDisturbance::CalcRMM() { static math::Vector<3> random_walk_std_dev(residual_magnetic_moment_.GetRandomWalkStandardDeviation_Am2()); static math::Vector<3> random_walk_limit(residual_magnetic_moment_.GetRandomWalkLimit_Am2()); static RandomWalk<3> random_walk(0.1, random_walk_std_dev, random_walk_limit); // [FIXME] step width is constant - static libra::NormalRand normal_random(0.0, residual_magnetic_moment_.GetRandomNoiseStandardDeviation_Am2(), global_randomization.MakeSeed()); + static randomization::NormalRand normal_random(0.0, residual_magnetic_moment_.GetRandomNoiseStandardDeviation_Am2(), global_randomization.MakeSeed()); rmm_b_Am2_ = residual_magnetic_moment_.GetConstantValue_b_Am2(); for (int i = 0; i < 3; ++i) { diff --git a/src/environment/local/atmosphere.cpp b/src/environment/local/atmosphere.cpp index fe693eac0..b0792bca4 100644 --- a/src/environment/local/atmosphere.cpp +++ b/src/environment/local/atmosphere.cpp @@ -78,7 +78,7 @@ double Atmosphere::CalcAirDensity_kg_m3(const double decimal_year, const Orbit& double Atmosphere::AddNoise(const double rho_kg_m3) { // RandomWalk rw(rho_kg_m3*rw_stepwidth_,rho_kg_m3*rw_stddev_,rho_kg_m3*rw_limit_); - libra::NormalRand nr(0.0, rho_kg_m3 * gauss_standard_deviation_rate_, global_randomization.MakeSeed()); + randomization::NormalRand nr(0.0, rho_kg_m3 * gauss_standard_deviation_rate_, global_randomization.MakeSeed()); double nrd = nr; return rho_kg_m3 + nrd; diff --git a/src/environment/local/geomagnetic_field.cpp b/src/environment/local/geomagnetic_field.cpp index f26c6e457..382978d62 100644 --- a/src/environment/local/geomagnetic_field.cpp +++ b/src/environment/local/geomagnetic_field.cpp @@ -44,7 +44,7 @@ void GeomagneticField::AddNoise(double* magnetic_field_array_i_nT) { static math::Vector<3> limit(random_walk_limit_nT_); static RandomWalk<3> random_walk(0.1, standard_deviation, limit); - static libra::NormalRand white_noise(0.0, white_noise_standard_deviation_nT_, global_randomization.MakeSeed()); + static randomization::NormalRand white_noise(0.0, white_noise_standard_deviation_nT_, global_randomization.MakeSeed()); for (int i = 0; i < 3; ++i) { magnetic_field_array_i_nT[i] += random_walk[i] + white_noise; diff --git a/src/math_physics/randomization/global_randomization.hpp b/src/math_physics/randomization/global_randomization.hpp index f63b63e82..a55ae9e98 100644 --- a/src/math_physics/randomization/global_randomization.hpp +++ b/src/math_physics/randomization/global_randomization.hpp @@ -33,7 +33,7 @@ class GlobalRandomization { private: static const unsigned int kMaxSeed = 0xffffffff; //!< Maximum value of seed - libra::MinimalStandardLcg base_randomizer_; //!< Base of global randomization + randomization::MinimalStandardLcg base_randomizer_; //!< Base of global randomization long seed_; //!< Seed of global randomization }; diff --git a/src/math_physics/randomization/minimal_standard_linear_congruential_generator.cpp b/src/math_physics/randomization/minimal_standard_linear_congruential_generator.cpp index 395a8943e..ccd179507 100644 --- a/src/math_physics/randomization/minimal_standard_linear_congruential_generator.cpp +++ b/src/math_physics/randomization/minimal_standard_linear_congruential_generator.cpp @@ -5,7 +5,7 @@ */ #include "minimal_standard_linear_congruential_generator.hpp" -using libra::MinimalStandardLcg; +using randomization::MinimalStandardLcg; #include diff --git a/src/math_physics/randomization/minimal_standard_linear_congruential_generator.hpp b/src/math_physics/randomization/minimal_standard_linear_congruential_generator.hpp index 70b97a695..9120faffd 100644 --- a/src/math_physics/randomization/minimal_standard_linear_congruential_generator.hpp +++ b/src/math_physics/randomization/minimal_standard_linear_congruential_generator.hpp @@ -7,7 +7,7 @@ #ifndef S2E_LIBRARY_RANDOMIZATION_MINIMAL_STANDARD_LINEAR_CONGRUENTIAL_GENERATOR_HPP_ #define S2E_LIBRARY_RANDOMIZATION_MINIMAL_STANDARD_LINEAR_CONGRUENTIAL_GENERATOR_HPP_ -namespace libra { +namespace randomization { /** * @class MinimalStandardLcg @@ -52,6 +52,6 @@ class MinimalStandardLcg { long seed_; //!< Seed of randomization }; -} // namespace libra +} // namespace randomization #endif // S2E_LIBRARY_RANDOMIZATION_MINIMAL_STANDARD_LINEAR_CONGRUENTIAL_GENERATOR_HPP_ diff --git a/src/math_physics/randomization/minimal_standard_linear_congruential_generator_with_shuffle.cpp b/src/math_physics/randomization/minimal_standard_linear_congruential_generator_with_shuffle.cpp index 95fbc7075..ea0a6bf43 100644 --- a/src/math_physics/randomization/minimal_standard_linear_congruential_generator_with_shuffle.cpp +++ b/src/math_physics/randomization/minimal_standard_linear_congruential_generator_with_shuffle.cpp @@ -5,7 +5,7 @@ */ #include "minimal_standard_linear_congruential_generator_with_shuffle.hpp" -using libra::MinimalStandardLcgWithShuffle; +using randomization::MinimalStandardLcgWithShuffle; MinimalStandardLcgWithShuffle::MinimalStandardLcgWithShuffle() : table_position_(0) { Initialize(); } diff --git a/src/math_physics/randomization/minimal_standard_linear_congruential_generator_with_shuffle.hpp b/src/math_physics/randomization/minimal_standard_linear_congruential_generator_with_shuffle.hpp index 6c42dddba..5c016291f 100644 --- a/src/math_physics/randomization/minimal_standard_linear_congruential_generator_with_shuffle.hpp +++ b/src/math_physics/randomization/minimal_standard_linear_congruential_generator_with_shuffle.hpp @@ -11,7 +11,7 @@ #include "minimal_standard_linear_congruential_generator.hpp" -namespace libra { +namespace randomization { /** * @class MinimalStandardLcgWithShuffle @@ -58,6 +58,6 @@ class MinimalStandardLcgWithShuffle { double mixing_table_[kTableSize]; //!< Mixing table }; -} // namespace libra +} // namespace randomization #endif // S2E_LIBRARY_RANDOMIZATION_MINIMAL_STANDARD_LINEAR_CONGRUENTIAL_GENERATOR_WITH_SHUFFLE_HPP_ diff --git a/src/math_physics/randomization/normal_randomization.cpp b/src/math_physics/randomization/normal_randomization.cpp index 02eb484b7..0e5c9e36c 100644 --- a/src/math_physics/randomization/normal_randomization.cpp +++ b/src/math_physics/randomization/normal_randomization.cpp @@ -4,7 +4,7 @@ * @note Ref: NUMERICAL RECIPES in C, p.216-p.217 */ #include "normal_randomization.hpp" -using libra::NormalRand; +using randomization::NormalRand; #include //DBL_EPSILON #include //sqrt, log; diff --git a/src/math_physics/randomization/normal_randomization.hpp b/src/math_physics/randomization/normal_randomization.hpp index 962126a0c..81e688091 100644 --- a/src/math_physics/randomization/normal_randomization.hpp +++ b/src/math_physics/randomization/normal_randomization.hpp @@ -8,9 +8,9 @@ #define S2E_LIBRARY_RANDOMIZATION_NORMAL_RANDOMIZATION_HPP_ #include "minimal_standard_linear_congruential_generator_with_shuffle.hpp" -using libra::MinimalStandardLcgWithShuffle; +using randomization::MinimalStandardLcgWithShuffle; -namespace libra { +namespace randomization { /** * @class NormalRand @@ -106,6 +106,6 @@ class NormalRand { bool is_empty_; //!< Flag to show the holder_ has available value }; -} // namespace libra +} // namespace randomization #endif // S2E_LIBRARY_RANDOMIZATION_NORMAL_RANDOMIZATION_HPP_ diff --git a/src/math_physics/randomization/random_walk.hpp b/src/math_physics/randomization/random_walk.hpp index befcd10de..5af240bf9 100644 --- a/src/math_physics/randomization/random_walk.hpp +++ b/src/math_physics/randomization/random_walk.hpp @@ -37,7 +37,7 @@ class RandomWalk : public math::OrdinaryDifferentialEquation { private: math::Vector limit_; //!< Limit of random walk - libra::NormalRand normal_randomizer_[N]; //!< Random walk excitation noise + randomization::NormalRand normal_randomizer_[N]; //!< Random walk excitation noise }; #include "random_walk_template_functions.hpp" // template function definisions.